Repository: ZhiChen902/SC2-PCR Branch: main Commit: 19961eae0a47 Files: 31 Total size: 1.2 MB Directory structure: gitextract_aendpbmi/ ├── .gitignore ├── 3DLoMatch.pkl ├── LICENSE ├── README.md ├── SC2_PCR.py ├── benchmark_utils.py ├── benchmark_utils_predator.py ├── benchmarks/ │ └── 3DLoMatch/ │ ├── 7-scenes-redkitchen/ │ │ └── gt.info │ ├── sun3d-home_at-home_at_scan1_2013_jan_1/ │ │ └── gt.info │ ├── sun3d-home_md-home_md_scan9_2012_sep_30/ │ │ └── gt.info │ ├── sun3d-hotel_uc-scan3/ │ │ └── gt.info │ ├── sun3d-hotel_umd-maryland_hotel1/ │ │ └── gt.info │ ├── sun3d-hotel_umd-maryland_hotel3/ │ │ └── gt.info │ ├── sun3d-mit_76_studyroom-76-1studyroom2/ │ │ └── gt.info │ └── sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika/ │ └── gt.info ├── common.py ├── config.py ├── config_json/ │ ├── config_3DLoMatch.json │ ├── config_3DMatch.json │ └── config_KITTI.json ├── dataset.py ├── environment.yml ├── evaluate_metric.py ├── test_3DLoMatch.py ├── test_3DMatch.py ├── test_KITTI.py └── utils/ ├── SE3.py ├── max_clique.py ├── pointcloud.py ├── sinkhorn.py └── timer.py ================================================ FILE CONTENTS ================================================ ================================================ FILE: .gitignore ================================================ # Byte-compiled / optimized / DLL files __pycache__/ *.py[cod] *$py.class # C extensions *.so # Distribution / packaging .Python build/ develop-eggs/ dist/ downloads/ eggs/ .eggs/ lib/ lib64/ parts/ sdist/ var/ wheels/ pip-wheel-metadata/ share/python-wheels/ *.egg-info/ .installed.cfg *.egg MANIFEST # PyInstaller # Usually these files are written by a python script from a template # before PyInstaller builds the exe, so as to inject date/other infos into it. *.manifest *.spec # Installer logs pip-log.txt pip-delete-this-directory.txt # Unit test / coverage reports htmlcov/ .tox/ .nox/ .coverage .coverage.* .cache nosetests.xml coverage.xml *.cover *.py,cover .hypothesis/ .pytest_cache/ # Translations *.mo *.pot # Django stuff: *.log local_settings.py db.sqlite3 db.sqlite3-journal # Flask stuff: instance/ .webassets-cache # Scrapy stuff: .scrapy # Sphinx documentation docs/_build/ # PyBuilder target/ # Jupyter Notebook .ipynb_checkpoints # IPython profile_default/ ipython_config.py # pyenv .python-version # pipenv # According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. # However, in case of collaboration, if having platform-specific dependencies or dependencies # having no cross-platform support, pipenv may install dependencies that don't work, or not # install all needed dependencies. #Pipfile.lock # PEP 582; used by e.g. github.com/David-OConnor/pyflow __pypackages__/ # Celery stuff celerybeat-schedule celerybeat.pid # SageMath parsed files *.sage.py # Environments .env .venv env/ venv/ ENV/ env.bak/ venv.bak/ # Spyder project settings .spyderproject .spyproject # Rope project settings .ropeproject # mkdocs documentation /site # mypy .mypy_cache/ .dmypy.json dmypy.json # Pyre type checker .pyre/ ================================================ FILE: LICENSE ================================================ MIT License Copyright (c) 2021 ZhiChen Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ================================================ FILE: README.md ================================================ # SC^2-PCR: A Second Order Spatial Compatibility for Efficient and Robust Point Cloud Registration (CVPR 2022) PyTorch implementation of the paper: [SC^2-PCR: A Second Order Spatial Compatibility for Efficient and Robust Point Cloud Registration](https://arxiv.org/abs/2203.14453). Zhi Chen, [Kun Sun](https://scholar.google.com/citations?user=Ay6kCm4AAAAJ&hl=en), Fan Yang, [Wenbing Tao](https://scholar.google.co.uk/citations?user=jRDPE2AAAAAJ&hl=zh-CN&oi=ao). ## Introduction In this paper, we present a second order spatial compatibility (SC^2) measure based method for efficient and robust point cloud registration (PCR), called SC^2-PCR. Firstly, we propose a second order spatial compatibility (SC^2) measure to compute the similarity between correspondences. It considers the global compatibility instead of local consistency, allowing for more distinctive clustering between inliers and outliers at early stage. Based on this measure, our registration pipeline employs a global spectral technique to find some reliable seeds from the initial correspondences. Then we design a two-stage strategy to expand each seed to a consensus set based on the SC^2 measure matrix. Finally, we feed each consensus set to a weighted SVD algorithm to generate a candidate rigid transformation and select the best model as the final result. Our method can guarantee to find a certain number of outlier-free consensus sets using fewer samplings, making the model estimation more efficient and robust. In addition, the proposed SC^2 measure is general and can be easily plugged into deep learning based frameworks. Extensive experiments are carried out to investigate the performance of our method. ![](figures/pipeline.png) ## Requirements If you are using conda, you may configure SC2-PCR as: conda env create -f environment.yml conda activate SC2_PCR ## 3DMatch ### Data preparation Downsample and extract FPFH and FCGF descriptors for each frame of the 3DMatch test dataset. [Here](https://drive.google.com/file/d/1kRwuTHlNPr9siENcEMddCO23Oaq0cz-X/view?usp=sharing) we provide the processed test set with pre-computed FPFH/FCGF descriptors. The data should be organized as follows: ``` --data--3DMatch ├── fragments │ ├── 7-scene-redkitechen/ | | ├── cloud_bin_0.ply | | ├── cloud_bin_0_fcgf.npz | | ├── cloud_bin_0_fpfh.npz │ | └── ... │ ├── sun3d-home_at-home_at_scan1_2013_jan_1/ │ └── ... ├── gt_result │ ├── 7-scene-redkitechen-evaluation/ | | ├── 3dmatch.log | | ├── gt.info | | ├── gt.log │ | └── ... │ ├── sun3d-home_at-home_at_scan1_2013_jan_1-evaluation/ │ └── ... ``` ### Testing Use the following command for testing. ```bash python ./test_3DMatch.py --config_path config_json/config_3DMatch.json ``` The CUDA_DEVICE and basic parameters can be changed in the json file. ## 3DLoMatch ### Data preparation FPFH and FCGF descriptors can be prepared in the same way as testing 3DMatch. If you want to test the [predator](https://github.com/prs-eth/OverlapPredator) descriptor, you should first follow the offical instruction of predator to extract the descriptors for 3DMatch dataset and organize the data as follows: ``` --data--3DLoMatch ├── 0.pth ├── 1.pth ├── ... └── 1780.pth ``` ### Testing Use the following command for testing. ```bash python ./test_3DLoMatch.py --config_path config_json/config_3DLoMatch.json ``` ## KITTI odometry ### Data preparation Downsample and extract FPFH and FCGF descriptors for each frame of the KITTI test dataset. The raw point clouds can be download from [KITTI Odometry website.](http://www.cvlibs.net/datasets/kitti/eval_odometry.php). For your convenience, [here](https://drive.google.com/drive/folders/1sxkHYjWHhSUE3IcvmZ2p1ziw1LqJqqfc?usp=sharing) we provide the pre-computed FPFH and FCGF descriptors for the KITTI test set. ``` --data--KITTI ├── fpfh_test │ ├── pair_0.npz | ├── pair_1.npz | ├── ... | └── pair_554.npz ├── fcgf_test │ ├── pair_0.npz | ├── pair_1.npz | ├── ... | └── pair_554.npz ``` ### Testing Use the following command for testing. ```bash python ./test_KITTI.py --config_path config_json/config_KITTI.json ``` ## Results ### 3DMatch We evaluate SC^2-PCR on the standard 3DMatch benchmarks: | Benchmark | RR(%) | RE(°) |TE(cm) | IP(%) | IR(%) | F1(%) | |:---------------|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:| | 3DMatch+FPFH | 83.98 | 2.18 | 6.56 | 72.48 | 78.33 | 75.10 | | 3DMatch+FCGF | 93.28 | 2.08 | 6.55 | 78.94 | 86.39 | 82.20 | ### 3DMatch We evaluate SC^2-PCR on the standard 3DLoMatch benchmarks: | Benchmark | RR(%) | RE(°) |TE(cm) | IP(%) | IR(%) | F1(%) | |:--------------------|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:| | 3DLoMatch+FCGF | 57.83 | 3.77 | 10.46 | 44.87 | 53.69 | 48.38 | | 3DLoMatch+Predator | 69.46 | 3.46 | 9.58 | 56.98 | 67.47 | 61.08 | ### KITTI odometry We evaluate SC^2-PCR on the standard KITTI benchmarks: | Benchmark | RR(%) | RE(°) |TE(cm) | IP(%) | IR(%) | F1(%) | |:---------------|:-----:|:-----:|:-----:|:-----:|:-----:|:-----:| | KITTI+FPFH | 99.64 | 0.32 | 7.23 | 93.63 | 95.89 | 94.63 | | KITTI+FCGF | 98.20 | 0.33 | 20.95 | 82.01 | 91.03 | 85.90 | ## Citation ```bibtex @InProceedings{Chen_2022_CVPR, author = {Chen, Zhi and Sun, Kun and Yang, Fan and Tao, Wenbing}, title = {SC2-PCR: A Second Order Spatial Compatibility for Efficient and Robust Point Cloud Registration}, booktitle = {Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR)}, month = {June}, year = {2022}, pages = {13221-13231} } ``` ## Acknowledgements - [PointDSC](https://github.com/XuyangBai/PointDSC) - [FCGF](https://github.com/chrischoy/FCGF) - [DGR](https://github.com/chrischoy/DeepGlobalRegistration) - [PREDATOR](https://github.com/prs-eth/OverlapPredator) ================================================ FILE: SC2_PCR.py ================================================ import torch from common import knn, rigid_transform_3d from utils.SE3 import transform import numpy as np class Matcher(): def __init__(self, inlier_threshold=0.10, num_node='all', use_mutual=True, d_thre=0.1, num_iterations=10, ratio=0.2, nms_radius=0.1, max_points=8000, k1=30, k2=20, select_scene=None, ): self.inlier_threshold = inlier_threshold self.num_node = num_node self.use_mutual = use_mutual self.d_thre = d_thre self.num_iterations = num_iterations # maximum iteration of power iteration algorithm self.ratio = ratio # the maximum ratio of seeds. self.max_points = max_points self.nms_radius = nms_radius self.k1 = k1 self.k2 = k2 def pick_seeds(self, dists, scores, R, max_num): """ Select seeding points using Non Maximum Suppression. (here we only support bs=1) Input: - dists: [bs, num_corr, num_corr] src keypoints distance matrix - scores: [bs, num_corr] initial confidence of each correspondence - R: float radius of nms - max_num: int maximum number of returned seeds Output: - picked_seeds: [bs, num_seeds] the index to the seeding correspondences """ assert scores.shape[0] == 1 # parallel Non Maximum Suppression (more efficient) score_relation = scores.T >= scores # [num_corr, num_corr], save the relation of leading_eig # score_relation[dists[0] >= R] = 1 # mask out the non-neighborhood node score_relation = score_relation.bool() | (dists[0] >= R).bool() is_local_max = score_relation.min(-1)[0].float() score_local_max = scores * is_local_max sorted_score = torch.argsort(score_local_max, dim=1, descending=True) # max_num = scores.shape[1] return_idx = sorted_score[:, 0: max_num].detach() return return_idx def cal_seed_trans(self, seeds, SC2_measure, src_keypts, tgt_keypts): """ Calculate the transformation for each seeding correspondences. Input: - seeds: [bs, num_seeds] the index to the seeding correspondence - SC2_measure: [bs, num_corr, num_channels] - src_keypts: [bs, num_corr, 3] - tgt_keypts: [bs, num_corr, 3] Output: leading eigenvector - final_trans: [bs, 4, 4] best transformation matrix (after post refinement) for each batch. """ bs, num_corr, num_channels = SC2_measure.shape[0], SC2_measure.shape[1], SC2_measure.shape[2] k1 = self.k1 k2 = self.k2 if k1 > num_channels: k1 = 4 k2 = 4 ################################# # The first stage consensus set sampling # Finding the k1 nearest neighbors around each seed ################################# sorted_score = torch.argsort(SC2_measure, dim=2, descending=True) knn_idx = sorted_score[:, :, 0: k1] sorted_value, _ = torch.sort(SC2_measure, dim=2, descending=True) idx_tmp = knn_idx.contiguous().view([bs, -1]) idx_tmp = idx_tmp[:, :, None] idx_tmp = idx_tmp.expand(-1, -1, 3) ################################# # construct the local SC2 measure of each consensus subset obtained in the first stage. ################################# src_knn = src_keypts.gather(dim=1, index=idx_tmp).view([bs, -1, k1, 3]) # [bs, num_seeds, k, 3] tgt_knn = tgt_keypts.gather(dim=1, index=idx_tmp).view([bs, -1, k1, 3]) src_dist = ((src_knn[:, :, :, None, :] - src_knn[:, :, None, :, :]) ** 2).sum(-1) ** 0.5 tgt_dist = ((tgt_knn[:, :, :, None, :] - tgt_knn[:, :, None, :, :]) ** 2).sum(-1) ** 0.5 cross_dist = torch.abs(src_dist - tgt_dist) local_hard_SC_measure = (cross_dist < self.d_thre).float() local_SC2_measure = torch.matmul(local_hard_SC_measure[:, :, :1, :], local_hard_SC_measure) ################################# # perform second stage consensus set sampling ################################# sorted_score = torch.argsort(local_SC2_measure, dim=3, descending=True) knn_idx_fine = sorted_score[:, :, :, 0: k2] ################################# # construct the soft SC2 matrix of the consensus set ################################# num = knn_idx_fine.shape[1] knn_idx_fine = knn_idx_fine.contiguous().view([bs, num, -1])[:, :, :, None] knn_idx_fine = knn_idx_fine.expand(-1, -1, -1, 3) src_knn_fine = src_knn.gather(dim=2, index=knn_idx_fine).view([bs, -1, k2, 3]) # [bs, num_seeds, k, 3] tgt_knn_fine = tgt_knn.gather(dim=2, index=knn_idx_fine).view([bs, -1, k2, 3]) src_dist = ((src_knn_fine[:, :, :, None, :] - src_knn_fine[:, :, None, :, :]) ** 2).sum(-1) ** 0.5 tgt_dist = ((tgt_knn_fine[:, :, :, None, :] - tgt_knn_fine[:, :, None, :, :]) ** 2).sum(-1) ** 0.5 cross_dist = torch.abs(src_dist - tgt_dist) local_hard_measure = (cross_dist < self.d_thre * 2).float() local_SC2_measure = torch.matmul(local_hard_measure, local_hard_measure) / k2 local_SC_measure = torch.clamp(1 - cross_dist ** 2 / self.d_thre ** 2, min=0) # local_SC2_measure = local_SC_measure * local_SC2_measure local_SC2_measure = local_SC_measure local_SC2_measure = local_SC2_measure.view([-1, k2, k2]) ################################# # Power iteratation to get the inlier probability ################################# local_SC2_measure[:, torch.arange(local_SC2_measure.shape[1]), torch.arange(local_SC2_measure.shape[1])] = 0 total_weight = self.cal_leading_eigenvector(local_SC2_measure, method='power') total_weight = total_weight.view([bs, -1, k2]) total_weight = total_weight / (torch.sum(total_weight, dim=-1, keepdim=True) + 1e-6) ################################# # calculate the transformation by weighted least-squares for each subsets in parallel ################################# total_weight = total_weight.view([-1, k2]) src_knn = src_knn_fine tgt_knn = tgt_knn_fine src_knn, tgt_knn = src_knn.view([-1, k2, 3]), tgt_knn.view([-1, k2, 3]) ################################# # compute the rigid transformation for each seed by the weighted SVD ################################# seedwise_trans = rigid_transform_3d(src_knn, tgt_knn, total_weight) seedwise_trans = seedwise_trans.view([bs, -1, 4, 4]) ################################# # calculate the inlier number for each hypothesis, and find the best transformation for each point cloud pair ################################# pred_position = torch.einsum('bsnm,bmk->bsnk', seedwise_trans[:, :, :3, :3], src_keypts.permute(0, 2, 1)) + seedwise_trans[:, :, :3, 3:4] # [bs, num_seeds, num_corr, 3] ################################# # calculate the inlier number for each hypothesis, and find the best transformation for each point cloud pair ################################# pred_position = pred_position.permute(0, 1, 3, 2) L2_dis = torch.norm(pred_position - tgt_keypts[:, None, :, :], dim=-1) # [bs, num_seeds, num_corr] seedwise_fitness = torch.sum((L2_dis < self.inlier_threshold).float(), dim=-1) # [bs, num_seeds] batch_best_guess = seedwise_fitness.argmax(dim=1) best_guess_ratio = seedwise_fitness[0, batch_best_guess] final_trans = seedwise_trans.gather(dim=1,index=batch_best_guess[:, None, None, None].expand(-1, -1, 4, 4)).squeeze(1) return final_trans def cal_leading_eigenvector(self, M, method='power'): """ Calculate the leading eigenvector using power iteration algorithm or torch.symeig Input: - M: [bs, num_corr, num_corr] the compatibility matrix - method: select different method for calculating the learding eigenvector. Output: - solution: [bs, num_corr] leading eigenvector """ if method == 'power': # power iteration algorithm leading_eig = torch.ones_like(M[:, :, 0:1]) leading_eig_last = leading_eig for i in range(self.num_iterations): leading_eig = torch.bmm(M, leading_eig) leading_eig = leading_eig / (torch.norm(leading_eig, dim=1, keepdim=True) + 1e-6) if torch.allclose(leading_eig, leading_eig_last): break leading_eig_last = leading_eig leading_eig = leading_eig.squeeze(-1) return leading_eig elif method == 'eig': # cause NaN during back-prop e, v = torch.symeig(M, eigenvectors=True) leading_eig = v[:, :, -1] return leading_eig else: exit(-1) def cal_confidence(self, M, leading_eig, method='eig_value'): """ Calculate the confidence of the spectral matching solution based on spectral analysis. Input: - M: [bs, num_corr, num_corr] the compatibility matrix - leading_eig [bs, num_corr] the leading eigenvector of matrix M Output: - confidence """ if method == 'eig_value': # max eigenvalue as the confidence (Rayleigh quotient) max_eig_value = (leading_eig[:, None, :] @ M @ leading_eig[:, :, None]) / ( leading_eig[:, None, :] @ leading_eig[:, :, None]) confidence = max_eig_value.squeeze(-1) return confidence elif method == 'eig_value_ratio': # max eigenvalue / second max eigenvalue as the confidence max_eig_value = (leading_eig[:, None, :] @ M @ leading_eig[:, :, None]) / ( leading_eig[:, None, :] @ leading_eig[:, :, None]) # compute the second largest eigen-value B = M - max_eig_value * leading_eig[:, :, None] @ leading_eig[:, None, :] solution = torch.ones_like(B[:, :, 0:1]) for i in range(self.num_iterations): solution = torch.bmm(B, solution) solution = solution / (torch.norm(solution, dim=1, keepdim=True) + 1e-6) solution = solution.squeeze(-1) second_eig = solution second_eig_value = (second_eig[:, None, :] @ B @ second_eig[:, :, None]) / ( second_eig[:, None, :] @ second_eig[:, :, None]) confidence = max_eig_value / second_eig_value return confidence elif method == 'xMx': # max xMx as the confidence (x is the binary solution) # rank = torch.argsort(leading_eig, dim=1, descending=True)[:, 0:int(M.shape[1]*self.ratio)] # binary_sol = torch.zeros_like(leading_eig) # binary_sol[0, rank[0]] = 1 confidence = leading_eig[:, None, :] @ M @ leading_eig[:, :, None] confidence = confidence.squeeze(-1) / M.shape[1] return confidence def post_refinement(self, initial_trans, src_keypts, tgt_keypts, it_num, weights=None): """ Perform post refinement using the initial transformation matrix, only adopted during testing. Input - initial_trans: [bs, 4, 4] - src_keypts: [bs, num_corr, 3] - tgt_keypts: [bs, num_corr, 3] - weights: [bs, num_corr] Output: - final_trans: [bs, 4, 4] """ assert initial_trans.shape[0] == 1 inlier_threshold = 1.2 # inlier_threshold_list = [self.inlier_threshold] * it_num if self.inlier_threshold == 0.10: # for 3DMatch inlier_threshold_list = [0.10] * it_num else: # for KITTI inlier_threshold_list = [1.2] * it_num previous_inlier_num = 0 for inlier_threshold in inlier_threshold_list: warped_src_keypts = transform(src_keypts, initial_trans) L2_dis = torch.norm(warped_src_keypts - tgt_keypts, dim=-1) pred_inlier = (L2_dis < inlier_threshold)[0] # assume bs = 1 inlier_num = torch.sum(pred_inlier) if abs(int(inlier_num - previous_inlier_num)) < 1: break else: previous_inlier_num = inlier_num initial_trans = rigid_transform_3d( A=src_keypts[:, pred_inlier, :], B=tgt_keypts[:, pred_inlier, :], ## https://link.springer.com/article/10.1007/s10589-014-9643-2 # weights=None, weights=1 / (1 + (L2_dis / inlier_threshold) ** 2)[:, pred_inlier], # weights=((1-L2_dis/inlier_threshold)**2)[:, pred_inlier] ) return initial_trans def match_pair(self, src_keypts, tgt_keypts, src_features, tgt_features): N_src = src_features.shape[1] N_tgt = tgt_features.shape[1] # use all point or sample points. if self.num_node == 'all': src_sel_ind = np.arange(N_src) tgt_sel_ind = np.arange(N_tgt) else: src_sel_ind = np.random.choice(N_src, self.num_node) tgt_sel_ind = np.random.choice(N_tgt, self.num_node) src_desc = src_features[:, src_sel_ind, :] tgt_desc = tgt_features[:, tgt_sel_ind, :] src_keypts = src_keypts[:, src_sel_ind, :] tgt_keypts = tgt_keypts[:, tgt_sel_ind, :] # match points in feature space. distance = torch.sqrt(2 - 2 * (src_desc[0] @ tgt_desc[0].T) + 1e-6) distance = distance.unsqueeze(0) source_idx = torch.argmin(distance[0], dim=1) corr = torch.cat([torch.arange(source_idx.shape[0])[:, None].cuda(), source_idx[:, None]], dim=-1) # generate correspondences src_keypts_corr = src_keypts[:, corr[:, 0]] tgt_keypts_corr = tgt_keypts[:, corr[:, 1]] return src_keypts_corr, tgt_keypts_corr def SC2_PCR(self, src_keypts, tgt_keypts): """ Input: - src_keypts: [bs, num_corr, 3] - tgt_keypts: [bs, num_corr, 3] Output: - pred_trans: [bs, 4, 4], the predicted transformation matrix. - pred_labels: [bs, num_corr], the predicted inlier/outlier label (0,1), for classification loss calculation. """ bs, num_corr = src_keypts.shape[0], tgt_keypts.shape[1] ################################# # downsample points ################################# if num_corr > self.max_points: src_keypts = src_keypts[:, :self.max_points, :] tgt_keypts = tgt_keypts[:, :self.max_points, :] num_corr = self.max_points ################################# # compute cross dist ################################# src_dist = torch.norm((src_keypts[:, :, None, :] - src_keypts[:, None, :, :]), dim=-1) target_dist = torch.norm((tgt_keypts[:, :, None, :] - tgt_keypts[:, None, :, :]), dim=-1) cross_dist = torch.abs(src_dist - target_dist) ################################# # compute first order measure ################################# SC_dist_thre = self.d_thre SC_measure = torch.clamp(1.0 - cross_dist ** 2 / SC_dist_thre ** 2, min=0) hard_SC_measure = (cross_dist < SC_dist_thre).float() ################################# # select reliable seed correspondences ################################# confidence = self.cal_leading_eigenvector(SC_measure, method='power') seeds = self.pick_seeds(src_dist, confidence, R=self.nms_radius, max_num=int(num_corr * self.ratio)) ################################# # compute second order measure ################################# SC2_dist_thre = self.d_thre / 2 hard_SC_measure_tight = (cross_dist < SC2_dist_thre).float() seed_hard_SC_measure = hard_SC_measure.gather(dim=1, index=seeds[:, :, None].expand(-1, -1, num_corr)) seed_hard_SC_measure_tight = hard_SC_measure_tight.gather(dim=1, index=seeds[:, :, None].expand(-1, -1, num_corr)) SC2_measure = torch.matmul(seed_hard_SC_measure_tight, hard_SC_measure_tight) * seed_hard_SC_measure ################################# # compute the seed-wise transformations and select the best one ################################# final_trans = self.cal_seed_trans(seeds, SC2_measure, src_keypts, tgt_keypts) ################################# # refine the result by recomputing the transformation over the whole set ################################# final_trans = self.post_refinement(final_trans, src_keypts, tgt_keypts, 20) return final_trans def estimator(self, src_keypts, tgt_keypts, src_features, tgt_features): """ Input: - src_keypts: [bs, num_corr, 3] - tgt_keypts: [bs, num_corr, 3] - src_features: [bs, num_corr, C] - tgt_features: [bs, num_corr, C] Output: - pred_trans: [bs, 4, 4], the predicted transformation matrix - pred_trans: [bs, num_corr], the predicted inlier/outlier label (0,1) - src_keypts_corr: [bs, num_corr, 3], the source points in the matched correspondences - tgt_keypts_corr: [bs, num_corr, 3], the target points in the matched correspondences """ ################################# # generate coarse correspondences ################################# src_keypts_corr, tgt_keypts_corr = self.match_pair(src_keypts, tgt_keypts, src_features, tgt_features) ################################# # use the proposed SC2-PCR to estimate the rigid transformation ################################# pred_trans = self.SC2_PCR(src_keypts_corr, tgt_keypts_corr) frag1_warp = transform(src_keypts_corr, pred_trans) distance = torch.sum((frag1_warp - tgt_keypts_corr) ** 2, dim=-1) ** 0.5 pred_labels = (distance < self.inlier_threshold).float() return pred_trans, pred_labels, src_keypts_corr, tgt_keypts_corr ================================================ FILE: benchmark_utils.py ================================================ import torch import numpy as np import random import math import open3d as o3d from utils.pointcloud import make_point_cloud def exact_auc(errors, thresholds): """ Calculate the exact area under curve, borrow from https://github.com/magicleap/SuperGluePretrainedNetwork """ sort_idx = np.argsort(errors) errors = np.array(errors.copy())[sort_idx] recall = (np.arange(len(errors)) + 1) / len(errors) errors = np.r_[0., errors] recall = np.r_[0., recall] aucs = [] for t in thresholds: last_index = np.searchsorted(errors, t) r = np.r_[recall[:last_index], recall[last_index - 1]] e = np.r_[errors[:last_index], t] aucs.append(np.trapz(r, x=e) / t) return aucs def set_seed(seed=51): """ Set the random seed for reproduce the results. """ torch.manual_seed(seed) torch.cuda.manual_seed(seed) torch.cuda.manual_seed_all(seed) # if you are using multi-GPU. np.random.seed(seed) # Numpy module. random.seed(seed) # Python random module. torch.backends.cudnn.benchmark = False torch.backends.cudnn.deterministic = True def icp_refine(src_keypts, tgt_keypts, pred_trans): """ ICP algorithm to refine the initial transformation Input: - src_keypts [1, num_corr, 3] FloatTensor - tgt_keypts [1, num_corr, 3] FloatTensor - pred_trans [1, 4, 4] FloatTensor, initial transformation """ src_pcd = make_point_cloud(src_keypts.detach().cpu().numpy()[0]) tgt_pcd = make_point_cloud(tgt_keypts.detach().cpu().numpy()[0]) initial_trans = pred_trans[0].detach().cpu().numpy() # change the convension of transforamtion because open3d use left multi. refined_T = o3d.registration.registration_icp( src_pcd, tgt_pcd, 0.10, initial_trans, o3d.registration.TransformationEstimationPointToPoint()).transformation refined_T = torch.from_numpy(refined_T[None, :, :]).to(pred_trans.device).float() return refined_T def is_rotation_matrix(R): """ Checks if a matrix is a valid rotation matrix. Input: - R: [3, 3] rotation matrix Output: - True/False """ Rt = np.transpose(R) shouldBeIdentity = np.dot(Rt, R) I = np.identity(3, dtype=R.dtype) n = np.linalg.norm(I - shouldBeIdentity) return n < 1e-3 def rot_to_euler(R): """ Convert the rotation matrix to euler angles(degree) Input: - R: [3, 3] rotation matrix Output: - alpha. [3], the rotation angle (in degrees) along x,y,z axis. """ assert (is_rotation_matrix(R)) sy = math.sqrt(R[0, 0] * R[0, 0] + R[1, 0] * R[1, 0]) singular = sy < 1e-6 if not singular: x = math.atan2(R[2, 1], R[2, 2]) y = math.atan2(-R[2, 0], sy) z = math.atan2(R[1, 0], R[0, 0]) else: x = math.atan2(-R[1, 2], R[1, 1]) y = math.atan2(-R[2, 0], sy) z = 0 return np.array([x * 180 / np.pi, y * 180 / np.pi, z * 180 / np.pi]) ================================================ FILE: benchmark_utils_predator.py ================================================ """ Script for benchmarking the 3DMatch test dataset. Author: Zan Gojcic, Shengyu Huang Last modified: 30.11.2020 """ import numpy as np import os,sys,glob,torch,math from collections import defaultdict import nibabel.quaternions as nq def rotation_error(R1, R2): """ Torch batch implementation of the rotation error between the estimated and the ground truth rotatiom matrix. Rotation error is defined as r_e = \arccos(\frac{Trace(\mathbf{R}_{ij}^{T}\mathbf{R}_{ij}^{\mathrm{GT}) - 1}{2}) Args: R1 (torch tensor): Estimated rotation matrices [b,3,3] R2 (torch tensor): Ground truth rotation matrices [b,3,3] Returns: ae (torch tensor): Rotation error in angular degreees [b,1] """ R_ = torch.matmul(R1.transpose(1,2), R2) e = torch.stack([(torch.trace(R_[_, :, :]) - 1) / 2 for _ in range(R_.shape[0])], dim=0).unsqueeze(1) # Clamp the errors to the valid range (otherwise torch.acos() is nan) e = torch.clamp(e, -1, 1, out=None) ae = torch.acos(e) pi = torch.Tensor([math.pi]) ae = 180. * ae / pi.to(ae.device).type(ae.dtype) return ae def translation_error(t1, t2): """ Torch batch implementation of the rotation error between the estimated and the ground truth rotatiom matrix. Rotation error is defined as r_e = \arccos(\frac{Trace(\mathbf{R}_{ij}^{T}\mathbf{R}_{ij}^{\mathrm{GT}) - 1}{2}) Args: t1 (torch tensor): Estimated translation vectors [b,3,1] t2 (torch tensor): Ground truth translation vectors [b,3,1] Returns: te (torch tensor): translation error in meters [b,1] """ return torch.norm(t1-t2, dim=(1, 2)) def computeTransformationErr(trans, info): """ Computer the transformation error as an approximation of the RMSE of corresponding points. More informaiton at http://redwood-data.org/indoor/registration.html Args: trans (numpy array): transformation matrices [n,4,4] info (numpy array): covariance matrices of the gt transformation paramaters [n,4,4] Returns: p (float): transformation error """ t = trans[:3, 3] r = trans[:3, :3] q = nq.mat2quat(r) er = np.concatenate([t, q[1:]], axis=0) p = er.reshape(1, 6) @ info @ er.reshape(6, 1) / info[0, 0] return p.item() def read_trajectory(filename, dim=4): """ Function that reads a trajectory saved in the 3DMatch/Redwood format to a numpy array. Format specification can be found at http://redwood-data.org/indoor/fileformat.html Args: filename (str): path to the '.txt' file containing the trajectory data dim (int): dimension of the transformation matrix (4x4 for 3D data) Returns: final_keys (dict): indices of pairs with more than 30% overlap (only this ones are included in the gt file) traj (numpy array): gt pairwise transformation matrices for n pairs[n,dim, dim] """ with open(filename) as f: lines = f.readlines() # Extract the point cloud pairs keys = lines[0::(dim+1)] temp_keys = [] for i in range(len(keys)): temp_keys.append(keys[i].split('\t')[0:3]) final_keys = [] for i in range(len(temp_keys)): final_keys.append([temp_keys[i][0].strip(), temp_keys[i][1].strip(), temp_keys[i][2].strip()]) traj = [] for i in range(len(lines)): if i % 5 != 0: traj.append(lines[i].split('\t')[0:dim]) traj = np.asarray(traj, dtype=np.float).reshape(-1,dim,dim) final_keys = np.asarray(final_keys) return final_keys, traj def read_trajectory_info(filename, dim=6): """ Function that reads the trajectory information saved in the 3DMatch/Redwood format to a numpy array. Information file contains the variance-covariance matrix of the transformation paramaters. Format specification can be found at http://redwood-data.org/indoor/fileformat.html Args: filename (str): path to the '.txt' file containing the trajectory information data dim (int): dimension of the transformation matrix (4x4 for 3D data) Returns: n_frame (int): number of fragments in the scene cov_matrix (numpy array): covariance matrix of the transformation matrices for n pairs[n,dim, dim] """ with open(filename) as fid: contents = fid.readlines() n_pairs = len(contents) // 7 assert (len(contents) == 7 * n_pairs) info_list = [] n_frame = 0 for i in range(n_pairs): frame_idx0, frame_idx1, n_frame = [int(item) for item in contents[i * 7].strip().split()] info_matrix = np.concatenate( [np.fromstring(item, sep='\t').reshape(1, -1) for item in contents[i * 7 + 1:i * 7 + 7]], axis=0) info_list.append(info_matrix) cov_matrix = np.asarray(info_list, dtype=np.float).reshape(-1,dim,dim) return n_frame, cov_matrix def extract_corresponding_trajectors(est_pairs,gt_pairs, gt_traj): """ Extract only those transformation matrices from the ground truth trajectory that are also in the estimated trajectory. Args: est_pairs (numpy array): indices of point cloud pairs with enough estimated overlap [m, 3] gt_pairs (numpy array): indices of gt overlaping point cloud pairs [n,3] gt_traj (numpy array): 3d array of the gt transformation parameters [n,4,4] Returns: ext_traj (numpy array): gt transformation parameters for the point cloud pairs from est_pairs [m,4,4] """ ext_traj = np.zeros((len(est_pairs), 4, 4)) for est_idx, pair in enumerate(est_pairs): pair[2] = gt_pairs[0][2] gt_idx = np.where((gt_pairs == pair).all(axis=1))[0] ext_traj[est_idx,:,:] = gt_traj[gt_idx,:,:] return ext_traj def evaluate_registration(num_fragment, result, result_pairs, gt_pairs, gt, gt_info, err2=0.2): """ Evaluates the performance of the registration algorithm according to the evaluation protocol defined by the 3DMatch/Redwood datasets. The evaluation protocol can be found at http://redwood-data.org/indoor/registration.html Args: num_fragment (int): path to the '.txt' file containing the trajectory information data result (numpy array): estimated transformation matrices [n,4,4] result_pairs (numpy array): indices of the point cloud for which the transformation matrix was estimated (m,3) gt_pairs (numpy array): indices of the ground truth overlapping point cloud pairs (n,3) gt (numpy array): ground truth transformation matrices [n,4,4] gt_cov (numpy array): covariance matrix of the ground truth transfromation parameters [n,6,6] err2 (float): threshold for the RMSE of the gt correspondences (default: 0.2m) Returns: precision (float): mean registration precision over the scene (not so important because it can be increased see papers) recall (float): mean registration recall over the scene (deciding parameter for the performance of the algorithm) """ err2 = err2 ** 2 gt_mask = np.zeros((num_fragment, num_fragment), dtype=np.int) flags=[] for idx in range(gt_pairs.shape[0]): i = int(gt_pairs[idx,0]) j = int(gt_pairs[idx,1]) # Only non consecutive pairs are tested if j - i > 1: gt_mask[i, j] = idx n_gt = np.sum(gt_mask > 0) good = 0 n_res = 0 for idx in range(result_pairs.shape[0]): i = int(result_pairs[idx,0]) j = int(result_pairs[idx,1]) pose = result[idx,:,:] if gt_mask[i, j] > 0: n_res += 1 gt_idx = gt_mask[i, j] p = computeTransformationErr(np.linalg.inv(gt[gt_idx,:,:]) @ pose, gt_info[gt_idx,:,:]) if p <= err2: good += 1 flags.append(0) else: flags.append(1) else: flags.append(2) if n_res == 0: n_res += 1e6 precision = good * 1.0 / n_res recall = good * 1.0 / n_gt return precision, recall, flags ================================================ FILE: benchmarks/3DLoMatch/7-scenes-redkitchen/gt.info ================================================ 0 7 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12210.202100000000 2953.006840000000 0.000000000000 5000.000000000000 0.000000000000 -12210.202100000000 0.000000000000 2524.756100000000 0.000000000000 0.000000000000 5000.000000000000 -2953.006840000000 -2524.756100000000 0.000000000000 0.000000000000 -12210.202100000000 -2953.006840000000 34372.125000000000 1417.439820000000 -5971.215330000000 12210.202100000000 0.000000000000 -2524.756100000000 1417.439820000000 33469.312500000000 8417.902340000001 2953.006840000000 2524.756100000000 0.000000000000 -5971.215330000000 8417.902340000001 4510.429690000000 0 8 60 2940.000000000000 0.000000000000 0.000000000000 0.000000000000 7647.359860000000 2027.591550000000 0.000000000000 2940.000000000000 0.000000000000 -7647.359860000000 0.000000000000 3053.756100000000 0.000000000000 0.000000000000 2940.000000000000 -2027.591550000000 -3053.756100000000 0.000000000000 0.000000000000 -7647.359860000000 -2027.591550000000 21586.956999999999 2113.761960000000 -7965.160640000000 7647.359860000000 0.000000000000 -3053.756100000000 2113.761960000000 23219.214800000002 5328.437010000000 2027.591550000000 3053.756100000000 0.000000000000 -7965.160640000000 5328.437010000000 4889.844730000000 0 9 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10638.137699999999 1998.040770000000 0.000000000000 5000.000000000000 0.000000000000 -10638.137699999999 0.000000000000 3307.306400000000 0.000000000000 0.000000000000 5000.000000000000 -1998.040770000000 -3307.306400000000 0.000000000000 0.000000000000 -10638.137699999999 -1998.040770000000 25807.343799999999 1660.834840000000 -7662.884770000000 10638.137699999999 0.000000000000 -3307.306400000000 1660.834840000000 26938.597699999998 5246.650390000000 1998.040770000000 3307.306400000000 0.000000000000 -7662.884770000000 5246.650390000000 4376.456050000000 0 16 60 3500.000000000000 0.000000000000 0.000000000000 0.000000000000 7305.772460000000 1173.560060000000 0.000000000000 3500.000000000000 0.000000000000 -7305.772460000000 0.000000000000 2302.791500000000 0.000000000000 0.000000000000 3500.000000000000 -1173.560060000000 -2302.791500000000 0.000000000000 0.000000000000 -7305.772460000000 -1173.560060000000 17060.779299999998 879.650208000000 -4939.298830000000 7305.772460000000 0.000000000000 -2302.791500000000 879.650208000000 17966.177700000000 3028.451420000000 1173.560060000000 2302.791500000000 0.000000000000 -4939.298830000000 3028.451420000000 2509.195310000000 0 17 60 2127.000000000000 0.000000000000 0.000000000000 0.000000000000 5124.270510000000 1334.902340000000 0.000000000000 2127.000000000000 0.000000000000 -5124.270510000000 0.000000000000 1992.042970000000 0.000000000000 0.000000000000 2127.000000000000 -1334.902340000000 -1992.042970000000 0.000000000000 0.000000000000 -5124.270510000000 -1334.902340000000 13700.192400000000 1380.157470000000 -4937.223140000000 5124.270510000000 0.000000000000 -1992.042970000000 1380.157470000000 14612.388700000000 3432.271480000000 1334.902340000000 1992.042970000000 0.000000000000 -4937.223140000000 3432.271480000000 3067.616210000000 0 18 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10711.997100000001 1917.689450000000 0.000000000000 5000.000000000000 0.000000000000 -10711.997100000001 0.000000000000 3115.850340000000 0.000000000000 0.000000000000 5000.000000000000 -1917.689450000000 -3115.850340000000 0.000000000000 0.000000000000 -10711.997100000001 -1917.689450000000 26063.636699999999 1474.673100000000 -7044.731450000000 10711.997100000001 0.000000000000 -3115.850340000000 1474.673100000000 27065.539100000002 5079.894530000000 1917.689450000000 3115.850340000000 0.000000000000 -7044.731450000000 5079.894530000000 3982.231690000000 0 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9297.610350000001 1174.249020000000 0.000000000000 5000.000000000000 0.000000000000 -9297.610350000001 0.000000000000 3275.526610000000 0.000000000000 0.000000000000 5000.000000000000 -1174.249020000000 -3275.526610000000 0.000000000000 0.000000000000 -9297.610350000001 -1174.249020000000 20462.949199999999 1299.697140000000 -6867.975100000000 9297.610350000001 0.000000000000 -3275.526610000000 1299.697140000000 21862.875000000000 3464.075930000000 1174.249020000000 3275.526610000000 0.000000000000 -6867.975100000000 3464.075930000000 3977.037350000000 0 25 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13223.351600000000 3251.172360000000 0.000000000000 5000.000000000000 0.000000000000 -13223.351600000000 0.000000000000 3102.926030000000 0.000000000000 0.000000000000 5000.000000000000 -3251.172360000000 -3102.926030000000 0.000000000000 0.000000000000 -13223.351600000000 -3251.172360000000 38067.203099999999 1942.314700000000 -7967.844240000000 13223.351600000000 0.000000000000 -3102.926030000000 1942.314700000000 38247.660199999998 8900.333010000000 3251.172360000000 3102.926030000000 0.000000000000 -7967.844240000000 8900.333010000000 5429.598630000000 0 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11528.893599999999 2145.299560000000 0.000000000000 5000.000000000000 0.000000000000 -11528.893599999999 0.000000000000 -4267.468260000000 0.000000000000 0.000000000000 5000.000000000000 -2145.299560000000 4267.468260000000 0.000000000000 0.000000000000 -11528.893599999999 -2145.299560000000 28536.888700000000 -1674.476320000000 9646.434569999999 11528.893599999999 0.000000000000 4267.468260000000 -1674.476320000000 30804.328099999999 5228.844240000000 2145.299560000000 -4267.468260000000 0.000000000000 9646.434569999999 5228.844240000000 5235.357910000000 0 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10391.774400000000 -229.911026000000 0.000000000000 5000.000000000000 0.000000000000 -10391.774400000000 0.000000000000 -4088.688480000000 0.000000000000 0.000000000000 5000.000000000000 229.911026000000 4088.688480000000 0.000000000000 0.000000000000 -10391.774400000000 229.911026000000 22798.605500000001 85.861770600000 8516.400390000001 10391.774400000000 0.000000000000 4088.688480000000 85.861770600000 25589.974600000001 -285.032562000000 -229.911026000000 -4088.688480000000 0.000000000000 8516.400390000001 -285.032562000000 4430.192380000000 0 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9612.613280000000 -656.424377000000 0.000000000000 5000.000000000000 0.000000000000 -9612.613280000000 0.000000000000 -3416.051030000000 0.000000000000 0.000000000000 5000.000000000000 656.424377000000 3416.051030000000 0.000000000000 0.000000000000 -9612.613280000000 656.424377000000 19639.666000000001 454.167328000000 6885.587890000000 9612.613280000000 0.000000000000 3416.051030000000 454.167328000000 22010.433600000000 -1262.046880000000 -656.424377000000 -3416.051030000000 0.000000000000 6885.587890000000 -1262.046880000000 3712.229250000000 0 33 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8523.642580000000 -1414.166870000000 0.000000000000 5000.000000000000 0.000000000000 -8523.642580000000 0.000000000000 -1484.834720000000 0.000000000000 0.000000000000 5000.000000000000 1414.166870000000 1484.834720000000 0.000000000000 0.000000000000 -8523.642580000000 1414.166870000000 15640.502899999999 983.811218000000 3075.908690000000 8523.642580000000 0.000000000000 1484.834720000000 983.811218000000 16945.763700000000 -2547.323730000000 -1414.166870000000 -1484.834720000000 0.000000000000 3075.908690000000 -2547.323730000000 2731.274170000000 0 34 60 3670.000000000000 0.000000000000 0.000000000000 0.000000000000 5227.837890000000 -98.508834800000 0.000000000000 3670.000000000000 0.000000000000 -5227.837890000000 0.000000000000 1133.112550000000 0.000000000000 0.000000000000 3670.000000000000 98.508834800000 -1133.112550000000 0.000000000000 0.000000000000 -5227.837890000000 98.508834800000 7567.572750000000 -31.379207600000 -1635.315310000000 5227.837890000000 0.000000000000 -1133.112550000000 -31.379207600000 8133.190430000000 -100.594940000000 -98.508834800000 1133.112550000000 0.000000000000 -1635.315310000000 -100.594940000000 626.862610000000 0 36 60 4945.000000000000 0.000000000000 0.000000000000 0.000000000000 11267.022499999999 2381.595210000000 0.000000000000 4945.000000000000 0.000000000000 -11267.022499999999 0.000000000000 3374.782960000000 0.000000000000 0.000000000000 4945.000000000000 -2381.595210000000 -3374.782960000000 0.000000000000 0.000000000000 -11267.022499999999 -2381.595210000000 28498.078099999999 1855.024780000000 -7830.616210000000 11267.022499999999 0.000000000000 -3374.782960000000 1855.024780000000 29586.240200000000 6110.899410000000 2381.595210000000 3374.782960000000 0.000000000000 -7830.616210000000 6110.899410000000 4560.088380000000 0 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10411.724600000000 1645.716920000000 0.000000000000 5000.000000000000 0.000000000000 -10411.724600000000 0.000000000000 1955.823360000000 0.000000000000 0.000000000000 5000.000000000000 -1645.716920000000 -1955.823360000000 0.000000000000 0.000000000000 -10411.724600000000 -1645.716920000000 24529.910199999998 964.453064000000 -4387.402830000000 10411.724600000000 0.000000000000 -1955.823360000000 964.453064000000 24964.607400000001 4284.263670000000 1645.716920000000 1955.823360000000 0.000000000000 -4387.402830000000 4284.263670000000 2722.198730000000 0 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9329.358399999999 718.045044000000 0.000000000000 5000.000000000000 0.000000000000 -9329.358399999999 0.000000000000 931.715942000000 0.000000000000 0.000000000000 5000.000000000000 -718.045044000000 -931.715942000000 0.000000000000 0.000000000000 -9329.358399999999 -718.045044000000 19823.814500000000 243.192368000000 -1667.537230000000 9329.358399999999 0.000000000000 -931.715942000000 243.192368000000 19980.738300000001 2073.827390000000 718.045044000000 931.715942000000 0.000000000000 -1667.537230000000 2073.827390000000 1287.261720000000 0 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13795.589800000000 3774.247800000000 0.000000000000 5000.000000000000 0.000000000000 -13795.589800000000 0.000000000000 -1720.364500000000 0.000000000000 0.000000000000 5000.000000000000 -3774.247800000000 1720.364500000000 0.000000000000 0.000000000000 -13795.589800000000 -3774.247800000000 41653.601600000002 -1256.028810000000 4496.085940000000 13795.589800000000 0.000000000000 1720.364500000000 -1256.028810000000 39678.816400000003 10560.762699999999 3774.247800000000 -1720.364500000000 0.000000000000 4496.085940000000 10560.762699999999 4274.560060000000 0 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13874.237300000001 4000.970700000000 0.000000000000 5000.000000000000 0.000000000000 -13874.237300000001 0.000000000000 -1567.137940000000 0.000000000000 0.000000000000 5000.000000000000 -4000.970700000000 1567.137940000000 0.000000000000 0.000000000000 -13874.237300000001 -4000.970700000000 42313.011700000003 -1182.931880000000 4025.156740000000 13874.237300000001 0.000000000000 1567.137940000000 -1182.931880000000 40043.914100000002 11211.805700000001 4000.970700000000 -1567.137940000000 0.000000000000 4025.156740000000 11211.805700000001 4583.428220000000 0 43 60 4884.000000000000 0.000000000000 0.000000000000 0.000000000000 13583.022499999999 4218.896000000000 0.000000000000 4884.000000000000 0.000000000000 -13583.022499999999 0.000000000000 -1569.279790000000 0.000000000000 0.000000000000 4884.000000000000 -4218.896000000000 1569.279790000000 0.000000000000 0.000000000000 -13583.022499999999 -4218.896000000000 41996.656300000002 -1211.657590000000 3990.619630000000 13583.022499999999 0.000000000000 1569.279790000000 -1211.657590000000 39363.886700000003 11858.942400000000 4218.896000000000 -1569.279790000000 0.000000000000 3990.619630000000 11858.942400000000 4978.040530000000 0 44 60 4343.000000000000 0.000000000000 0.000000000000 0.000000000000 12376.637699999999 3956.686520000000 0.000000000000 4343.000000000000 0.000000000000 -12376.637699999999 0.000000000000 -921.256287000000 0.000000000000 0.000000000000 4343.000000000000 -3956.686520000000 921.256287000000 0.000000000000 0.000000000000 -12376.637699999999 -3956.686520000000 39168.050799999997 -740.596619000000 2463.221190000000 12376.637699999999 0.000000000000 921.256287000000 -740.596619000000 36295.992200000001 11341.436500000000 3956.686520000000 -921.256287000000 0.000000000000 2463.221190000000 11341.436500000000 4609.375980000000 0 45 60 4288.000000000000 0.000000000000 0.000000000000 0.000000000000 12130.670899999999 4075.019530000000 0.000000000000 4288.000000000000 0.000000000000 -12130.670899999999 0.000000000000 190.687714000000 0.000000000000 0.000000000000 4288.000000000000 -4075.019530000000 -190.687714000000 0.000000000000 0.000000000000 -12130.670899999999 -4075.019530000000 38436.667999999998 217.107666000000 -481.495850000000 12130.670899999999 0.000000000000 -190.687714000000 217.107666000000 35475.718800000002 11603.487300000001 4075.019530000000 190.687714000000 0.000000000000 -481.495850000000 11603.487300000001 5048.103030000000 0 46 60 3610.000000000000 0.000000000000 0.000000000000 0.000000000000 9909.697270000001 3333.438480000000 0.000000000000 3610.000000000000 0.000000000000 -9909.697270000001 0.000000000000 1656.724850000000 0.000000000000 0.000000000000 3610.000000000000 -3333.438480000000 -1656.724850000000 0.000000000000 0.000000000000 -9909.697270000001 -3333.438480000000 30487.958999999999 1532.831050000000 -4418.769040000000 9909.697270000001 0.000000000000 -1656.724850000000 1532.831050000000 28868.539100000002 9226.884770000001 3333.438480000000 1656.724850000000 0.000000000000 -4418.769040000000 9226.884770000001 4741.207030000000 0 47 60 2241.000000000000 0.000000000000 0.000000000000 0.000000000000 6001.209470000000 1987.929080000000 0.000000000000 2241.000000000000 0.000000000000 -6001.209470000000 0.000000000000 1746.349370000000 0.000000000000 0.000000000000 2241.000000000000 -1987.929080000000 -1746.349370000000 0.000000000000 0.000000000000 -6001.209470000000 -1987.929080000000 17993.546900000001 1542.154300000000 -4626.656740000000 6001.209470000000 0.000000000000 -1746.349370000000 1542.154300000000 17727.820299999999 5387.374020000000 1987.929080000000 1746.349370000000 0.000000000000 -4626.656740000000 5387.374020000000 3431.065670000000 0 48 60 2508.000000000000 0.000000000000 0.000000000000 0.000000000000 6673.774900000000 2196.189210000000 0.000000000000 2508.000000000000 0.000000000000 -6673.774900000000 0.000000000000 2110.895260000000 0.000000000000 0.000000000000 2508.000000000000 -2196.189210000000 -2110.895260000000 0.000000000000 0.000000000000 -6673.774900000000 -2196.189210000000 19878.044900000001 1832.434810000000 -5562.061040000000 6673.774900000000 0.000000000000 -2110.895260000000 1832.434810000000 19796.937500000000 5925.408690000000 2196.189210000000 2110.895260000000 0.000000000000 -5562.061040000000 5925.408690000000 3976.842290000000 0 49 60 2070.000000000000 0.000000000000 0.000000000000 0.000000000000 5504.915040000000 1863.228390000000 0.000000000000 2070.000000000000 0.000000000000 -5504.915040000000 0.000000000000 1907.668330000000 0.000000000000 0.000000000000 2070.000000000000 -1863.228390000000 -1907.668330000000 0.000000000000 0.000000000000 -5504.915040000000 -1863.228390000000 16460.998000000000 1700.126950000000 -5036.161130000000 5504.915040000000 0.000000000000 -1907.668330000000 1700.126950000000 16552.531299999999 5015.273440000000 1863.228390000000 1907.668330000000 0.000000000000 -5036.161130000000 5015.273440000000 3609.248050000000 0 50 60 2077.000000000000 0.000000000000 0.000000000000 0.000000000000 5575.812990000000 1884.130740000000 0.000000000000 2077.000000000000 0.000000000000 -5575.812990000000 0.000000000000 1797.978030000000 0.000000000000 0.000000000000 2077.000000000000 -1884.130740000000 -1797.978030000000 0.000000000000 0.000000000000 -5575.812990000000 -1884.130740000000 16824.068400000000 1607.136600000000 -4768.985840000000 5575.812990000000 0.000000000000 -1797.978030000000 1607.136600000000 16729.515599999999 5115.610840000000 1884.130740000000 1797.978030000000 0.000000000000 -4768.985840000000 5115.610840000000 3475.901120000000 0 51 60 1967.000000000000 0.000000000000 0.000000000000 0.000000000000 5384.763180000000 1910.958620000000 0.000000000000 1967.000000000000 0.000000000000 -5384.763180000000 0.000000000000 1657.597050000000 0.000000000000 0.000000000000 1967.000000000000 -1910.958620000000 -1657.597050000000 0.000000000000 0.000000000000 -5384.763180000000 -1910.958620000000 16688.861300000000 1587.810180000000 -4468.035160000000 5384.763180000000 0.000000000000 -1657.597050000000 1587.810180000000 16354.829100000001 5261.686040000000 1910.958620000000 1657.597050000000 0.000000000000 -4468.035160000000 5261.686040000000 3455.852540000000 0 52 60 2257.000000000000 0.000000000000 0.000000000000 0.000000000000 6025.153320000000 2003.331670000000 0.000000000000 2257.000000000000 0.000000000000 -6025.153320000000 0.000000000000 1966.990840000000 0.000000000000 0.000000000000 2257.000000000000 -2003.331670000000 -1966.990840000000 0.000000000000 0.000000000000 -6025.153320000000 -2003.331670000000 18022.375000000000 1729.295040000000 -5209.063960000000 6025.153320000000 0.000000000000 -1966.990840000000 1729.295040000000 17987.093799999999 5407.795410000000 2003.331670000000 1966.990840000000 0.000000000000 -5209.063960000000 5407.795410000000 3708.770020000000 0 53 60 2603.000000000000 0.000000000000 0.000000000000 0.000000000000 6867.698240000000 2277.476320000000 0.000000000000 2603.000000000000 0.000000000000 -6867.698240000000 0.000000000000 2397.200200000000 0.000000000000 0.000000000000 2603.000000000000 -2277.476320000000 -2397.200200000000 0.000000000000 0.000000000000 -6867.698240000000 -2277.476320000000 20273.226600000002 2088.597660000000 -6308.565920000000 6867.698240000000 0.000000000000 -2397.200200000000 2088.597660000000 20490.394499999999 6068.125980000000 2277.476320000000 2397.200200000000 0.000000000000 -6308.565920000000 6068.125980000000 4422.375490000000 0 59 60 4776.000000000000 0.000000000000 0.000000000000 0.000000000000 10217.717800000000 1475.224730000000 0.000000000000 4776.000000000000 0.000000000000 -10217.717800000000 0.000000000000 2370.767090000000 0.000000000000 0.000000000000 4776.000000000000 -1475.224730000000 -2370.767090000000 0.000000000000 0.000000000000 -10217.717800000000 -1475.224730000000 24121.152300000002 646.232361000000 -4840.785640000000 10217.717800000000 0.000000000000 -2370.767090000000 646.232361000000 24755.650399999999 3809.353520000000 1475.224730000000 2370.767090000000 0.000000000000 -4840.785640000000 3809.353520000000 2306.751460000000 1 6 60 4698.000000000000 0.000000000000 0.000000000000 0.000000000000 9510.342769999999 1958.431880000000 0.000000000000 4698.000000000000 0.000000000000 -9510.342769999999 0.000000000000 2657.172120000000 0.000000000000 0.000000000000 4698.000000000000 -1958.431880000000 -2657.172120000000 0.000000000000 0.000000000000 -9510.342769999999 -1958.431880000000 23491.043000000001 1218.698490000000 -5514.714360000000 9510.342769999999 0.000000000000 -2657.172120000000 1218.698490000000 23324.505900000000 5531.427250000000 1958.431880000000 2657.172120000000 0.000000000000 -5514.714360000000 5531.427250000000 3784.353270000000 1 7 60 2680.000000000000 0.000000000000 0.000000000000 0.000000000000 5976.207520000000 1449.922850000000 0.000000000000 2680.000000000000 0.000000000000 -5976.207520000000 0.000000000000 1860.472410000000 0.000000000000 0.000000000000 2680.000000000000 -1449.922850000000 -1860.472410000000 0.000000000000 0.000000000000 -5976.207520000000 -1449.922850000000 15472.499000000000 1036.438110000000 -4134.912110000000 5976.207520000000 0.000000000000 -1860.472410000000 1036.438110000000 15616.198200000001 3848.831540000000 1449.922850000000 1860.472410000000 0.000000000000 -4134.912110000000 3848.831540000000 2729.849610000000 1 9 60 4724.000000000000 0.000000000000 0.000000000000 0.000000000000 8804.417970000000 1561.751100000000 0.000000000000 4724.000000000000 0.000000000000 -8804.417970000000 0.000000000000 3243.971190000000 0.000000000000 0.000000000000 4724.000000000000 -1561.751100000000 -3243.971190000000 0.000000000000 0.000000000000 -8804.417970000000 -1561.751100000000 19212.939500000000 1478.932500000000 -6602.207030000000 8804.417970000000 0.000000000000 -3243.971190000000 1478.932500000000 20416.875000000000 3983.139650000000 1561.751100000000 3243.971190000000 0.000000000000 -6602.207030000000 3983.139650000000 3889.398440000000 1 18 60 4087.000000000000 0.000000000000 0.000000000000 0.000000000000 7812.197270000000 1331.869750000000 0.000000000000 4087.000000000000 0.000000000000 -7812.197270000000 0.000000000000 2589.360350000000 0.000000000000 0.000000000000 4087.000000000000 -1331.869750000000 -2589.360350000000 0.000000000000 0.000000000000 -7812.197270000000 -1331.869750000000 17143.128900000000 1093.527830000000 -5270.881350000000 7812.197270000000 0.000000000000 -2589.360350000000 1093.527830000000 18026.927700000000 3331.197510000000 1331.869750000000 2589.360350000000 0.000000000000 -5270.881350000000 3331.197510000000 2887.313960000000 1 19 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9399.859380000000 1406.237920000000 0.000000000000 5000.000000000000 0.000000000000 -9399.859380000000 0.000000000000 2664.071780000000 0.000000000000 0.000000000000 5000.000000000000 -1406.237920000000 -2664.071780000000 0.000000000000 0.000000000000 -9399.859380000000 -1406.237920000000 21375.041000000001 1113.690550000000 -5516.181640000000 9399.859380000000 0.000000000000 -2664.071780000000 1113.690550000000 21872.789100000002 4039.108640000000 1406.237920000000 2664.071780000000 0.000000000000 -5516.181640000000 4039.108640000000 3269.646730000000 1 20 60 2963.000000000000 0.000000000000 0.000000000000 0.000000000000 4724.031250000000 314.822357000000 0.000000000000 2963.000000000000 0.000000000000 -4724.031250000000 0.000000000000 1920.060060000000 0.000000000000 0.000000000000 2963.000000000000 -314.822357000000 -1920.060060000000 0.000000000000 0.000000000000 -4724.031250000000 -314.822357000000 9061.186519999999 515.915771000000 -3465.757320000000 4724.031250000000 0.000000000000 -1920.060060000000 515.915771000000 9948.657230000001 1188.860470000000 314.822357000000 1920.060060000000 0.000000000000 -3465.757320000000 1188.860470000000 2048.820560000000 1 25 60 2327.000000000000 0.000000000000 0.000000000000 0.000000000000 5941.959960000000 1652.886600000000 0.000000000000 2327.000000000000 0.000000000000 -5941.959960000000 0.000000000000 1907.437010000000 0.000000000000 0.000000000000 2327.000000000000 -1652.886600000000 -1907.437010000000 0.000000000000 0.000000000000 -5941.959960000000 -1652.886600000000 16810.089800000002 1433.753300000000 -4782.992680000000 5941.959960000000 0.000000000000 -1907.437010000000 1433.753300000000 17129.486300000000 4303.953130000000 1652.886600000000 1907.437010000000 0.000000000000 -4782.992680000000 4303.953130000000 3227.877930000000 1 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10271.943400000000 1091.013060000000 0.000000000000 5000.000000000000 0.000000000000 -10271.943400000000 0.000000000000 -3642.377440000000 0.000000000000 0.000000000000 5000.000000000000 -1091.013060000000 3642.377440000000 0.000000000000 0.000000000000 -10271.943400000000 -1091.013060000000 23489.392599999999 -262.356171000000 6966.707520000000 10271.943400000000 0.000000000000 3642.377440000000 -262.356171000000 25035.960899999998 3020.233150000000 1091.013060000000 -3642.377440000000 0.000000000000 6966.707520000000 3020.233150000000 4463.917970000000 1 33 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7923.100100000000 -1544.969600000000 0.000000000000 5000.000000000000 0.000000000000 -7923.100100000000 0.000000000000 -1682.794920000000 0.000000000000 0.000000000000 5000.000000000000 1544.969600000000 1682.794920000000 0.000000000000 0.000000000000 -7923.100100000000 1544.969600000000 13548.571300000000 1065.850710000000 3029.700930000000 7923.100100000000 0.000000000000 1682.794920000000 1065.850710000000 14950.790000000001 -2536.266360000000 -1544.969600000000 -1682.794920000000 0.000000000000 3029.700930000000 -2536.266360000000 2894.563230000000 1 36 60 2060.000000000000 0.000000000000 0.000000000000 0.000000000000 3884.446780000000 654.399719000000 0.000000000000 2060.000000000000 0.000000000000 -3884.446780000000 0.000000000000 1543.955570000000 0.000000000000 0.000000000000 2060.000000000000 -654.399719000000 -1543.955570000000 0.000000000000 0.000000000000 -3884.446780000000 -654.399719000000 8139.222170000000 595.697510000000 -3044.352780000000 3884.446780000000 0.000000000000 -1543.955570000000 595.697510000000 8953.404300000000 1516.876220000000 654.399719000000 1543.955570000000 0.000000000000 -3044.352780000000 1516.876220000000 1691.966920000000 1 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9359.709960000000 947.481506000000 0.000000000000 5000.000000000000 0.000000000000 -9359.709960000000 0.000000000000 1778.957400000000 0.000000000000 0.000000000000 5000.000000000000 -947.481506000000 -1778.957400000000 0.000000000000 0.000000000000 -9359.709960000000 -947.481506000000 19991.869100000000 574.832458000000 -3368.233150000000 9359.709960000000 0.000000000000 -1778.957400000000 574.832458000000 20478.675800000001 2404.723630000000 947.481506000000 1778.957400000000 0.000000000000 -3368.233150000000 2404.723630000000 1818.909180000000 1 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8784.515630000000 306.391754000000 0.000000000000 5000.000000000000 0.000000000000 -8784.515630000000 0.000000000000 1186.390990000000 0.000000000000 0.000000000000 5000.000000000000 -306.391754000000 -1186.390990000000 0.000000000000 0.000000000000 -8784.515630000000 -306.391754000000 17522.503900000000 254.805984000000 -1881.514400000000 8784.515630000000 0.000000000000 -1186.390990000000 254.805984000000 17953.468799999999 991.416199000000 306.391754000000 1186.390990000000 0.000000000000 -1881.514400000000 991.416199000000 1199.848630000000 1 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8805.480470000000 699.115601000000 0.000000000000 5000.000000000000 0.000000000000 -8805.480470000000 0.000000000000 1857.265010000000 0.000000000000 0.000000000000 5000.000000000000 -699.115601000000 -1857.265010000000 0.000000000000 0.000000000000 -8805.480470000000 -699.115601000000 18277.226600000002 640.934387000000 -3562.402100000000 8805.480470000000 0.000000000000 -1857.265010000000 640.934387000000 18501.103500000001 2250.649660000000 699.115601000000 1857.265010000000 0.000000000000 -3562.402100000000 2250.649660000000 2088.554930000000 1 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12837.537100000000 3702.863040000000 0.000000000000 5000.000000000000 0.000000000000 -12837.537100000000 0.000000000000 -1141.941770000000 0.000000000000 0.000000000000 5000.000000000000 -3702.863040000000 1141.941770000000 0.000000000000 0.000000000000 -12837.537100000000 -3702.863040000000 36634.636700000003 -709.055969000000 2505.065190000000 12837.537100000000 0.000000000000 1141.941770000000 -709.055969000000 34475.730499999998 9697.972659999999 3702.863040000000 -1141.941770000000 0.000000000000 2505.065190000000 9697.972659999999 3801.521000000000 1 42 60 4098.000000000000 0.000000000000 0.000000000000 0.000000000000 10667.516600000001 3216.024900000000 0.000000000000 4098.000000000000 0.000000000000 -10667.516600000001 0.000000000000 -974.725403000000 0.000000000000 0.000000000000 4098.000000000000 -3216.024900000000 974.725403000000 0.000000000000 0.000000000000 -10667.516600000001 -3216.024900000000 30960.228500000001 -573.404358000000 2137.067380000000 10667.516600000001 0.000000000000 974.725403000000 -573.404358000000 29096.156299999999 8479.427729999999 3216.024900000000 -974.725403000000 0.000000000000 2137.067380000000 8479.427729999999 3588.743160000000 1 43 60 3057.000000000000 0.000000000000 0.000000000000 0.000000000000 8222.717769999999 2817.871340000000 0.000000000000 3057.000000000000 0.000000000000 -8222.717769999999 0.000000000000 -204.633865000000 0.000000000000 0.000000000000 3057.000000000000 -2817.871340000000 204.633865000000 0.000000000000 0.000000000000 -8222.717769999999 -2817.871340000000 25093.775399999999 -32.181175200000 253.273407000000 8222.717769999999 0.000000000000 204.633865000000 -32.181175200000 22974.939500000000 7667.896000000000 2817.871340000000 -204.633865000000 0.000000000000 253.273407000000 7667.896000000000 3256.553710000000 1 44 60 2461.000000000000 0.000000000000 0.000000000000 0.000000000000 6839.964840000000 2476.242680000000 0.000000000000 2461.000000000000 0.000000000000 -6839.964840000000 0.000000000000 523.244995000000 0.000000000000 0.000000000000 2461.000000000000 -2476.242680000000 -523.244995000000 0.000000000000 0.000000000000 -6839.964840000000 -2476.242680000000 21637.085899999998 605.567200000000 -1571.758670000000 6839.964840000000 0.000000000000 -523.244995000000 605.567200000000 19659.955099999999 6921.515140000000 2476.242680000000 523.244995000000 0.000000000000 -1571.758670000000 6921.515140000000 3087.860840000000 1 45 60 2941.000000000000 0.000000000000 0.000000000000 0.000000000000 7980.909670000000 2871.830320000000 0.000000000000 2941.000000000000 0.000000000000 -7980.909670000000 0.000000000000 1218.833130000000 0.000000000000 0.000000000000 2941.000000000000 -2871.830320000000 -1218.833130000000 0.000000000000 0.000000000000 -7980.909670000000 -2871.830320000000 24593.105500000001 1207.507930000000 -3285.004390000000 7980.909670000000 0.000000000000 -1218.833130000000 1207.507930000000 22815.439500000000 7844.439450000000 2871.830320000000 1218.833130000000 0.000000000000 -3285.004390000000 7844.439450000000 3930.639160000000 1 46 60 2902.000000000000 0.000000000000 0.000000000000 0.000000000000 7700.841310000000 2707.920900000000 0.000000000000 2902.000000000000 0.000000000000 -7700.841310000000 0.000000000000 1611.901730000000 0.000000000000 0.000000000000 2902.000000000000 -2707.920900000000 -1611.901730000000 0.000000000000 0.000000000000 -7700.841310000000 -2707.920900000000 23118.562500000000 1488.037960000000 -4215.088870000000 7700.841310000000 0.000000000000 -1611.901730000000 1488.037960000000 21933.515599999999 7251.308590000000 2707.920900000000 1611.901730000000 0.000000000000 -4215.088870000000 7251.308590000000 3993.579350000000 1 59 60 2425.000000000000 0.000000000000 0.000000000000 0.000000000000 4545.438480000000 502.649445000000 0.000000000000 2425.000000000000 0.000000000000 -4545.438480000000 0.000000000000 1540.568850000000 0.000000000000 0.000000000000 2425.000000000000 -502.649445000000 -1540.568850000000 0.000000000000 0.000000000000 -4545.438480000000 -502.649445000000 9408.333979999999 340.230408000000 -2844.579830000000 4545.438480000000 0.000000000000 -1540.568850000000 340.230408000000 10205.675800000001 1191.783570000000 502.649445000000 1540.568850000000 0.000000000000 -2844.579830000000 1191.783570000000 1329.013550000000 2 5 60 3654.000000000000 0.000000000000 0.000000000000 0.000000000000 9007.341800000000 2674.919680000000 0.000000000000 3654.000000000000 0.000000000000 -9007.341800000000 0.000000000000 3026.354980000000 0.000000000000 0.000000000000 3654.000000000000 -2674.919680000000 -3026.354980000000 0.000000000000 0.000000000000 -9007.341800000000 -2674.919680000000 25067.744100000000 2392.093260000000 -7473.842770000000 9007.341800000000 0.000000000000 -3026.354980000000 2392.093260000000 25034.101600000002 6723.410160000000 2674.919680000000 3026.354980000000 0.000000000000 -7473.842770000000 6723.410160000000 5242.987790000000 2 10 60 3071.000000000000 0.000000000000 0.000000000000 0.000000000000 7648.357420000000 2986.698000000000 0.000000000000 3071.000000000000 0.000000000000 -7648.357420000000 0.000000000000 2152.639890000000 0.000000000000 0.000000000000 3071.000000000000 -2986.698000000000 -2152.639890000000 0.000000000000 0.000000000000 -7648.357420000000 -2986.698000000000 22504.902300000002 2116.980710000000 -5344.425780000000 7648.357420000000 0.000000000000 -2152.639890000000 2116.980710000000 20850.507799999999 7570.666020000000 2986.698000000000 2152.639890000000 0.000000000000 -5344.425780000000 7570.666020000000 4908.541020000000 2 15 60 3043.000000000000 0.000000000000 0.000000000000 0.000000000000 7547.055660000000 928.953430000000 0.000000000000 3043.000000000000 0.000000000000 -7547.055660000000 0.000000000000 2130.778560000000 0.000000000000 0.000000000000 3043.000000000000 -928.953430000000 -2130.778560000000 0.000000000000 0.000000000000 -7547.055660000000 -928.953430000000 19516.544900000001 739.864441000000 -5250.295900000000 7547.055660000000 0.000000000000 -2130.778560000000 739.864441000000 20630.644499999999 2298.210210000000 928.953430000000 2130.778560000000 0.000000000000 -5250.295900000000 2298.210210000000 2072.302250000000 2 26 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11526.061500000000 2751.206790000000 0.000000000000 5000.000000000000 0.000000000000 -11526.061500000000 0.000000000000 3270.246830000000 0.000000000000 0.000000000000 5000.000000000000 -2751.206790000000 -3270.246830000000 0.000000000000 0.000000000000 -11526.061500000000 -2751.206790000000 28753.117200000001 1880.690310000000 -7656.038090000000 11526.061500000000 0.000000000000 -3270.246830000000 1880.690310000000 29344.918000000001 6373.179200000000 2751.206790000000 3270.246830000000 0.000000000000 -7656.038090000000 6373.179200000000 4716.547850000000 2 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8146.324710000000 -894.500610000000 0.000000000000 5000.000000000000 0.000000000000 -8146.324710000000 0.000000000000 -304.443420000000 0.000000000000 0.000000000000 5000.000000000000 894.500610000000 304.443420000000 0.000000000000 0.000000000000 -8146.324710000000 894.500610000000 14230.990200000000 162.288483000000 636.019287000000 8146.324710000000 0.000000000000 304.443420000000 162.288483000000 14129.076200000000 -1334.819340000000 -894.500610000000 -304.443420000000 0.000000000000 636.019287000000 -1334.819340000000 1280.284060000000 2 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12413.441400000000 5672.087400000000 0.000000000000 5000.000000000000 0.000000000000 -12413.441400000000 0.000000000000 2684.462400000000 0.000000000000 0.000000000000 5000.000000000000 -5672.087400000000 -2684.462400000000 0.000000000000 0.000000000000 -12413.441400000000 -5672.087400000000 37923.425799999997 2963.598880000000 -6818.377440000000 12413.441400000000 0.000000000000 -2684.462400000000 2963.598880000000 33143.394500000002 14240.596700000000 5672.087400000000 2684.462400000000 0.000000000000 -6818.377440000000 14240.596700000000 8942.742190000001 2 45 60 4474.000000000000 0.000000000000 0.000000000000 0.000000000000 11319.818400000000 5029.042970000000 0.000000000000 4474.000000000000 0.000000000000 -11319.818400000000 0.000000000000 3269.293700000000 0.000000000000 0.000000000000 4474.000000000000 -5029.042970000000 -3269.293700000000 0.000000000000 0.000000000000 -11319.818400000000 -5029.042970000000 34798.050799999997 3706.366700000000 -8246.049800000001 11319.818400000000 0.000000000000 -3269.293700000000 3706.366700000000 31437.752000000000 12884.941400000000 5029.042970000000 3269.293700000000 0.000000000000 -8246.049800000001 12884.941400000000 8662.089840000001 3 6 60 4256.000000000000 0.000000000000 0.000000000000 0.000000000000 7579.038090000000 -411.407715000000 0.000000000000 4256.000000000000 0.000000000000 -7579.038090000000 0.000000000000 4697.210940000000 0.000000000000 0.000000000000 4256.000000000000 411.407715000000 -4697.210940000000 0.000000000000 0.000000000000 -7579.038090000000 411.407715000000 14875.636699999999 -386.177979000000 -8397.356449999999 7579.038090000000 0.000000000000 -4697.210940000000 -386.177979000000 19731.043000000001 -270.187622000000 -411.407715000000 4697.210940000000 0.000000000000 -8397.356449999999 -270.187622000000 5710.841800000000 3 7 60 3834.000000000000 0.000000000000 0.000000000000 0.000000000000 6433.454590000000 -830.642578000000 0.000000000000 3834.000000000000 0.000000000000 -6433.454590000000 0.000000000000 4691.221190000000 0.000000000000 0.000000000000 3834.000000000000 830.642578000000 -4691.221190000000 0.000000000000 0.000000000000 -6433.454590000000 830.642578000000 11823.744100000000 -1004.109990000000 -7874.584960000000 6433.454590000000 0.000000000000 -4691.221190000000 -1004.109990000000 17255.660199999998 -1125.480470000000 -830.642578000000 4691.221190000000 0.000000000000 -7874.584960000000 -1125.480470000000 6214.627440000000 3 15 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9493.070309999999 -1765.218510000000 0.000000000000 5000.000000000000 0.000000000000 -9493.070309999999 0.000000000000 5279.791500000000 0.000000000000 0.000000000000 5000.000000000000 1765.218510000000 -5279.791500000000 0.000000000000 0.000000000000 -9493.070309999999 1765.218510000000 19986.955099999999 -1821.074710000000 -9683.031250000000 9493.070309999999 0.000000000000 -5279.791500000000 -1821.074710000000 25092.437500000000 -3247.910890000000 -1765.218510000000 5279.791500000000 0.000000000000 -9683.031250000000 -3247.910890000000 6892.822750000000 3 19 60 4265.000000000000 0.000000000000 0.000000000000 0.000000000000 7652.726560000000 -1043.909910000000 0.000000000000 4265.000000000000 0.000000000000 -7652.726560000000 0.000000000000 4996.566410000000 0.000000000000 0.000000000000 4265.000000000000 1043.909910000000 -4996.566410000000 0.000000000000 0.000000000000 -7652.726560000000 1043.909910000000 14666.264600000000 -1217.205930000000 -8929.257809999999 7652.726560000000 0.000000000000 -4996.566410000000 -1217.205930000000 20229.226600000002 -1766.654050000000 -1043.909910000000 4996.566410000000 0.000000000000 -8929.257809999999 -1766.654050000000 6505.530760000000 3 25 60 4747.000000000000 0.000000000000 0.000000000000 0.000000000000 8638.886720000000 -1343.842410000000 0.000000000000 4747.000000000000 0.000000000000 -8638.886720000000 0.000000000000 6096.410160000000 0.000000000000 0.000000000000 4747.000000000000 1343.842410000000 -6096.410160000000 0.000000000000 0.000000000000 -8638.886720000000 1343.842410000000 16841.273399999998 -1724.916630000000 -11049.429700000001 8638.886720000000 0.000000000000 -6096.410160000000 -1724.916630000000 23851.923800000000 -2318.158940000000 -1343.842410000000 6096.410160000000 0.000000000000 -11049.429700000001 -2318.158940000000 8810.067380000000 3 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8128.096680000000 -1011.569700000000 0.000000000000 5000.000000000000 0.000000000000 -8128.096680000000 0.000000000000 -584.198853000000 0.000000000000 0.000000000000 5000.000000000000 1011.569700000000 584.198853000000 0.000000000000 0.000000000000 -8128.096680000000 1011.569700000000 14083.044900000001 68.383316000000 795.265869000000 8128.096680000000 0.000000000000 584.198853000000 68.383316000000 13863.940399999999 -1636.688720000000 -1011.569700000000 -584.198853000000 0.000000000000 795.265869000000 -1636.688720000000 940.422668000000 3 32 60 3463.000000000000 0.000000000000 0.000000000000 0.000000000000 4965.597170000000 -1207.123780000000 0.000000000000 3463.000000000000 0.000000000000 -4965.597170000000 0.000000000000 -52.321418800000 0.000000000000 0.000000000000 3463.000000000000 1207.123780000000 52.321418800000 0.000000000000 0.000000000000 -4965.597170000000 1207.123780000000 7906.093260000000 -10.419385000000 254.499969000000 4965.597170000000 0.000000000000 52.321418800000 -10.419385000000 7875.771970000000 -1698.743290000000 -1207.123780000000 -52.321418800000 0.000000000000 254.499969000000 -1698.743290000000 1007.383670000000 3 36 60 3190.000000000000 0.000000000000 0.000000000000 0.000000000000 4320.091310000000 -1269.624630000000 0.000000000000 3190.000000000000 0.000000000000 -4320.091310000000 0.000000000000 3878.509770000000 0.000000000000 0.000000000000 3190.000000000000 1269.624630000000 -3878.509770000000 0.000000000000 0.000000000000 -4320.091310000000 1269.624630000000 7217.327150000000 -1493.100100000000 -5435.334470000000 4320.091310000000 0.000000000000 -3878.509770000000 -1493.100100000000 11391.827100000000 -1532.565310000000 -1269.624630000000 3878.509770000000 0.000000000000 -5435.334470000000 -1532.565310000000 5443.984860000000 3 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8593.054690000001 -2082.538090000000 0.000000000000 5000.000000000000 0.000000000000 -8593.054690000001 0.000000000000 5620.880860000000 0.000000000000 0.000000000000 5000.000000000000 2082.538090000000 -5620.880860000000 0.000000000000 0.000000000000 -8593.054690000001 2082.538090000000 16871.783200000002 -2227.835450000000 -9602.113280000000 8593.054690000001 0.000000000000 -5620.880860000000 -2227.835450000000 22419.468799999999 -3526.425050000000 -2082.538090000000 5620.880860000000 0.000000000000 -9602.113280000000 -3526.425050000000 7798.354000000000 3 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8502.123050000000 -1904.940060000000 0.000000000000 5000.000000000000 0.000000000000 -8502.123050000000 0.000000000000 5661.504880000000 0.000000000000 0.000000000000 5000.000000000000 1904.940060000000 -5661.504880000000 0.000000000000 0.000000000000 -8502.123050000000 1904.940060000000 16405.294900000001 -2058.157960000000 -9611.498050000000 8502.123050000000 0.000000000000 -5661.504880000000 -2058.157960000000 22149.781299999999 -3147.573000000000 -1904.940060000000 5661.504880000000 0.000000000000 -9611.498050000000 -3147.573000000000 7663.989750000000 3 39 60 4619.000000000000 0.000000000000 0.000000000000 0.000000000000 7783.093260000000 -1481.343260000000 0.000000000000 4619.000000000000 0.000000000000 -7783.093260000000 0.000000000000 5364.850100000000 0.000000000000 0.000000000000 4619.000000000000 1481.343260000000 -5364.850100000000 0.000000000000 0.000000000000 -7783.093260000000 1481.343260000000 14692.086900000000 -1666.740970000000 -9165.428710000000 7783.093260000000 0.000000000000 -5364.850100000000 -1666.740970000000 20387.722699999998 -2333.152100000000 -1481.343260000000 5364.850100000000 0.000000000000 -9165.428710000000 -2333.152100000000 7107.251460000000 3 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10704.981400000001 2071.539310000000 0.000000000000 5000.000000000000 0.000000000000 -10704.981400000001 0.000000000000 5820.911130000000 0.000000000000 0.000000000000 5000.000000000000 -2071.539310000000 -5820.911130000000 0.000000000000 0.000000000000 -10704.981400000001 -2071.539310000000 24613.347699999998 2456.681640000000 -12338.290000000001 10704.981400000001 0.000000000000 -5820.911130000000 2456.681640000000 30292.138700000000 4682.384770000000 2071.539310000000 5820.911130000000 0.000000000000 -12338.290000000001 4682.384770000000 8401.768550000001 3 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8271.142580000000 -2090.086180000000 0.000000000000 5000.000000000000 0.000000000000 -8271.142580000000 0.000000000000 6333.010740000000 0.000000000000 0.000000000000 5000.000000000000 2090.086180000000 -6333.010740000000 0.000000000000 0.000000000000 -8271.142580000000 2090.086180000000 15466.851600000000 -2634.464110000000 -10546.835900000000 8271.142580000000 0.000000000000 -6333.010740000000 -2634.464110000000 22539.630900000000 -3396.467040000000 -2090.086180000000 6333.010740000000 0.000000000000 -10546.835900000000 -3396.467040000000 9173.838870000000 4 8 60 4701.000000000000 0.000000000000 0.000000000000 0.000000000000 10990.556600000000 235.949097000000 0.000000000000 4701.000000000000 0.000000000000 -10990.556600000000 0.000000000000 4784.711430000000 0.000000000000 0.000000000000 4701.000000000000 -235.949097000000 -4784.711430000000 0.000000000000 0.000000000000 -10990.556600000000 -235.949097000000 26783.146499999999 200.565826000000 -11291.783200000000 10990.556600000000 0.000000000000 -4784.711430000000 200.565826000000 31431.581999999999 604.592712000000 235.949097000000 4784.711430000000 0.000000000000 -11291.783200000000 604.592712000000 6028.567870000000 4 16 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9354.194340000000 -1484.574340000000 0.000000000000 5000.000000000000 0.000000000000 -9354.194340000000 0.000000000000 2780.968990000000 0.000000000000 0.000000000000 5000.000000000000 1484.574340000000 -2780.968990000000 0.000000000000 0.000000000000 -9354.194340000000 1484.574340000000 19770.970700000002 -765.948303000000 -5217.941890000000 9354.194340000000 0.000000000000 -2780.968990000000 -765.948303000000 21169.333999999999 -2405.883300000000 -1484.574340000000 2780.968990000000 0.000000000000 -5217.941890000000 -2405.883300000000 2895.241460000000 4 17 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9705.715819999999 -821.856995000000 0.000000000000 5000.000000000000 0.000000000000 -9705.715819999999 0.000000000000 3739.321530000000 0.000000000000 0.000000000000 5000.000000000000 821.856995000000 -3739.321530000000 0.000000000000 0.000000000000 -9705.715819999999 821.856995000000 21098.947300000000 -378.161255000000 -7535.533690000000 9705.715819999999 0.000000000000 -3739.321530000000 -378.161255000000 23521.242200000001 -1007.045720000000 -821.856995000000 3739.321530000000 0.000000000000 -7535.533690000000 -1007.045720000000 4122.998540000000 4 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9910.185550000000 -195.890884000000 0.000000000000 5000.000000000000 0.000000000000 -9910.185550000000 0.000000000000 3455.757810000000 0.000000000000 0.000000000000 5000.000000000000 195.890884000000 -3455.757810000000 0.000000000000 0.000000000000 -9910.185550000000 195.890884000000 21754.433600000000 4.113144870000 -6989.491210000000 9910.185550000000 0.000000000000 -3455.757810000000 4.113144870000 24088.675800000001 398.165680000000 -195.890884000000 3455.757810000000 0.000000000000 -6989.491210000000 398.165680000000 3784.359130000000 4 21 60 3984.000000000000 0.000000000000 0.000000000000 0.000000000000 8953.137699999999 -1007.425600000000 0.000000000000 3984.000000000000 0.000000000000 -8953.137699999999 0.000000000000 4864.489260000000 0.000000000000 0.000000000000 3984.000000000000 1007.425600000000 -4864.489260000000 0.000000000000 0.000000000000 -8953.137699999999 1007.425600000000 22088.246100000000 -1106.666020000000 -11375.032200000000 8953.137699999999 0.000000000000 -4864.489260000000 -1106.666020000000 27619.087899999999 -2016.485110000000 -1007.425600000000 4864.489260000000 0.000000000000 -11375.032200000000 -2016.485110000000 6747.472170000000 4 24 60 4052.000000000000 0.000000000000 0.000000000000 0.000000000000 10205.027300000000 -602.807068000000 0.000000000000 4052.000000000000 0.000000000000 -10205.027300000000 0.000000000000 5110.705570000000 0.000000000000 0.000000000000 4052.000000000000 602.807068000000 -5110.705570000000 0.000000000000 0.000000000000 -10205.027300000000 602.807068000000 26494.441400000000 -836.326050000000 -12922.021500000001 10205.027300000000 0.000000000000 -5110.705570000000 -836.326050000000 32405.458999999999 -1621.174800000000 -602.807068000000 5110.705570000000 0.000000000000 -12922.021500000001 -1621.174800000000 7164.469240000000 4 28 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10446.277300000000 -1014.448490000000 0.000000000000 5000.000000000000 0.000000000000 -10446.277300000000 0.000000000000 -3429.631840000000 0.000000000000 0.000000000000 5000.000000000000 1014.448490000000 3429.631840000000 0.000000000000 0.000000000000 -10446.277300000000 1014.448490000000 24017.978500000001 350.268799000000 7742.930660000000 10446.277300000000 0.000000000000 3429.631840000000 350.268799000000 26011.521499999999 -1828.713990000000 -1014.448490000000 -3429.631840000000 0.000000000000 7742.930660000000 -1828.713990000000 4254.934570000000 4 29 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11470.825199999999 -333.735779000000 0.000000000000 5000.000000000000 0.000000000000 -11470.825199999999 0.000000000000 -4382.509280000000 0.000000000000 0.000000000000 5000.000000000000 333.735779000000 4382.509280000000 0.000000000000 0.000000000000 -11470.825199999999 333.735779000000 27816.531299999999 -1.911907200000 10105.373000000000 11470.825199999999 0.000000000000 4382.509280000000 -1.911907200000 30772.107400000001 -621.646362000000 -333.735779000000 -4382.509280000000 0.000000000000 10105.373000000000 -621.646362000000 5211.849610000000 4 35 60 3532.000000000000 0.000000000000 0.000000000000 0.000000000000 8025.152830000000 536.236450000000 0.000000000000 3532.000000000000 0.000000000000 -8025.152830000000 0.000000000000 3470.155520000000 0.000000000000 0.000000000000 3532.000000000000 -536.236450000000 -3470.155520000000 0.000000000000 0.000000000000 -8025.152830000000 -536.236450000000 18829.998000000000 659.553040000000 -7988.810060000000 8025.152830000000 0.000000000000 -3470.155520000000 659.553040000000 22087.232400000001 1288.229000000000 536.236450000000 3470.155520000000 0.000000000000 -7988.810060000000 1288.229000000000 4225.658200000000 4 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9804.099609999999 -533.317078000000 0.000000000000 5000.000000000000 0.000000000000 -9804.099609999999 0.000000000000 3039.068120000000 0.000000000000 0.000000000000 5000.000000000000 533.317078000000 -3039.068120000000 0.000000000000 0.000000000000 -9804.099609999999 533.317078000000 21238.496100000000 -72.397369400000 -6135.634770000000 9804.099609999999 0.000000000000 -3039.068120000000 -72.397369400000 22828.652300000002 -454.955841000000 -533.317078000000 3039.068120000000 0.000000000000 -6135.634770000000 -454.955841000000 3215.793700000000 4 40 60 3895.000000000000 0.000000000000 0.000000000000 0.000000000000 8685.416020000001 824.098694000000 0.000000000000 3895.000000000000 0.000000000000 -8685.416020000001 0.000000000000 -1931.682620000000 0.000000000000 0.000000000000 3895.000000000000 -824.098694000000 1931.682620000000 0.000000000000 0.000000000000 -8685.416020000001 -824.098694000000 21706.793000000001 -236.275513000000 4331.057130000000 8685.416020000001 0.000000000000 1931.682620000000 -236.275513000000 21467.171900000001 2521.211180000000 824.098694000000 -1931.682620000000 0.000000000000 4331.057130000000 2521.211180000000 2707.371090000000 4 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12275.746100000000 2019.513670000000 0.000000000000 5000.000000000000 0.000000000000 -12275.746100000000 0.000000000000 -3336.854000000000 0.000000000000 0.000000000000 5000.000000000000 -2019.513670000000 3336.854000000000 0.000000000000 0.000000000000 -12275.746100000000 -2019.513670000000 32204.423800000000 -1512.936040000000 8317.478520000001 12275.746100000000 0.000000000000 3336.854000000000 -1512.936040000000 33054.894500000002 5240.685550000000 2019.513670000000 -3336.854000000000 0.000000000000 8317.478520000001 5240.685550000000 4453.647460000000 4 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12338.087900000000 2674.953130000000 0.000000000000 5000.000000000000 0.000000000000 -12338.087900000000 0.000000000000 -3048.465580000000 0.000000000000 0.000000000000 5000.000000000000 -2674.953130000000 3048.465580000000 0.000000000000 0.000000000000 -12338.087900000000 -2674.953130000000 32600.841799999998 -1642.332400000000 7499.555660000000 12338.087900000000 0.000000000000 3048.465580000000 -1642.332400000000 33050.761700000003 6780.707030000000 2674.953130000000 -3048.465580000000 0.000000000000 7499.555660000000 6780.707030000000 4499.896970000000 4 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11681.127899999999 2232.801760000000 0.000000000000 5000.000000000000 0.000000000000 -11681.127899999999 0.000000000000 3740.020510000000 0.000000000000 0.000000000000 5000.000000000000 -2232.801760000000 -3740.020510000000 0.000000000000 0.000000000000 -11681.127899999999 -2232.801760000000 28793.710899999998 1582.912600000000 -8623.263670000000 11681.127899999999 0.000000000000 -3740.020510000000 1582.912600000000 31127.240200000000 5305.510250000000 2232.801760000000 3740.020510000000 0.000000000000 -8623.263670000000 5305.510250000000 5147.372070000000 4 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11713.282200000000 2173.110350000000 0.000000000000 5000.000000000000 0.000000000000 -11713.282200000000 0.000000000000 3855.835450000000 0.000000000000 0.000000000000 5000.000000000000 -2173.110350000000 -3855.835450000000 0.000000000000 0.000000000000 -11713.282200000000 -2173.110350000000 28839.958999999999 1560.179440000000 -8951.598630000000 11713.282200000000 0.000000000000 -3855.835450000000 1560.179440000000 31260.886699999999 5170.677730000000 2173.110350000000 3855.835450000000 0.000000000000 -8951.598630000000 5170.677730000000 5055.335450000000 4 50 60 4495.000000000000 0.000000000000 0.000000000000 0.000000000000 10613.075199999999 1523.668950000000 0.000000000000 4495.000000000000 0.000000000000 -10613.075199999999 0.000000000000 3233.856930000000 0.000000000000 0.000000000000 4495.000000000000 -1523.668950000000 -3233.856930000000 0.000000000000 0.000000000000 -10613.075199999999 -1523.668950000000 25867.335899999998 1035.859130000000 -7527.774410000000 10613.075199999999 0.000000000000 -3233.856930000000 1035.859130000000 28176.421900000001 3686.243410000000 1523.668950000000 3233.856930000000 0.000000000000 -7527.774410000000 3686.243410000000 3737.318360000000 4 51 60 2961.000000000000 0.000000000000 0.000000000000 0.000000000000 7148.076660000000 1114.621090000000 0.000000000000 2961.000000000000 0.000000000000 -7148.076660000000 0.000000000000 1394.509520000000 0.000000000000 0.000000000000 2961.000000000000 -1114.621090000000 -1394.509520000000 0.000000000000 0.000000000000 -7148.076660000000 -1114.621090000000 17779.449199999999 499.443237000000 -3285.363530000000 7148.076660000000 0.000000000000 -1394.509520000000 499.443237000000 18331.765599999999 2721.584230000000 1114.621090000000 1394.509520000000 0.000000000000 -3285.363530000000 2721.584230000000 1499.411380000000 4 52 60 4652.000000000000 0.000000000000 0.000000000000 0.000000000000 10960.546899999999 1527.117430000000 0.000000000000 4652.000000000000 0.000000000000 -10960.546899999999 0.000000000000 3436.518800000000 0.000000000000 0.000000000000 4652.000000000000 -1527.117430000000 -3436.518800000000 0.000000000000 0.000000000000 -10960.546899999999 -1527.117430000000 26663.831999999999 1022.483830000000 -7990.132810000000 10960.546899999999 0.000000000000 -3436.518800000000 1022.483830000000 29196.646499999999 3700.628660000000 1527.117430000000 3436.518800000000 0.000000000000 -7990.132810000000 3700.628660000000 4020.313720000000 4 53 60 4767.000000000000 0.000000000000 0.000000000000 0.000000000000 11095.000000000000 1425.144530000000 0.000000000000 4767.000000000000 0.000000000000 -11095.000000000000 0.000000000000 3886.806150000000 0.000000000000 0.000000000000 4767.000000000000 -1425.144530000000 -3886.806150000000 0.000000000000 0.000000000000 -11095.000000000000 -1425.144530000000 26724.011699999999 1096.297490000000 -9026.979490000000 11095.000000000000 0.000000000000 -3886.806150000000 1096.297490000000 29651.974600000001 3449.822270000000 1425.144530000000 3886.806150000000 0.000000000000 -9026.979490000000 3449.822270000000 4541.528810000000 4 54 60 3930.000000000000 0.000000000000 0.000000000000 0.000000000000 7209.002930000000 -590.859558000000 0.000000000000 3930.000000000000 0.000000000000 -7209.002930000000 0.000000000000 3355.169430000000 0.000000000000 0.000000000000 3930.000000000000 590.859558000000 -3355.169430000000 0.000000000000 0.000000000000 -7209.002930000000 590.859558000000 15116.586900000000 -216.144333000000 -6516.764160000000 7209.002930000000 0.000000000000 -3355.169430000000 -216.144333000000 17599.152300000002 -422.025146000000 -590.859558000000 3355.169430000000 0.000000000000 -6516.764160000000 -422.025146000000 3830.560550000000 4 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6874.162110000000 -2213.178710000000 0.000000000000 5000.000000000000 0.000000000000 -6874.162110000000 0.000000000000 2843.459720000000 0.000000000000 0.000000000000 5000.000000000000 2213.178710000000 -2843.459720000000 0.000000000000 0.000000000000 -6874.162110000000 2213.178710000000 11601.985400000000 -1240.666990000000 -4118.570800000000 6874.162110000000 0.000000000000 -2843.459720000000 -1240.666990000000 12425.722700000000 -2846.217770000000 -2213.178710000000 2843.459720000000 0.000000000000 -4118.570800000000 -2846.217770000000 2956.496340000000 4 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9487.018550000001 -1571.414430000000 0.000000000000 5000.000000000000 0.000000000000 -9487.018550000001 0.000000000000 2034.056760000000 0.000000000000 0.000000000000 5000.000000000000 1571.414430000000 -2034.056760000000 0.000000000000 0.000000000000 -9487.018550000001 1571.414430000000 19930.658200000002 -716.070801000000 -3573.694340000000 9487.018550000001 0.000000000000 -2034.056760000000 -716.070801000000 20603.570299999999 -2751.277830000000 -1571.414430000000 2034.056760000000 0.000000000000 -3573.694340000000 -2751.277830000000 2001.061400000000 5 13 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11925.150400000000 308.791748000000 0.000000000000 5000.000000000000 0.000000000000 -11925.150400000000 0.000000000000 -3700.150630000000 0.000000000000 0.000000000000 5000.000000000000 -308.791748000000 3700.150630000000 0.000000000000 0.000000000000 -11925.150400000000 -308.791748000000 29786.732400000001 -322.653870000000 9166.253909999999 11925.150400000000 0.000000000000 3700.150630000000 -322.653870000000 32620.275399999999 1081.333740000000 308.791748000000 -3700.150630000000 0.000000000000 9166.253909999999 1081.333740000000 4000.422850000000 5 14 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11903.078100000001 -26.995672200000 0.000000000000 5000.000000000000 0.000000000000 -11903.078100000001 0.000000000000 -2613.323000000000 0.000000000000 0.000000000000 5000.000000000000 26.995672200000 2613.323000000000 0.000000000000 0.000000000000 -11903.078100000001 26.995672200000 29107.517599999999 -86.216049200000 6457.917480000000 11903.078100000001 0.000000000000 2613.323000000000 -86.216049200000 31250.066400000000 92.233299300000 -26.995672200000 -2613.323000000000 0.000000000000 6457.917480000000 92.233299300000 2786.522460000000 5 21 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10817.588900000001 21.676635700000 0.000000000000 5000.000000000000 0.000000000000 -10817.588900000001 0.000000000000 4369.466310000000 0.000000000000 0.000000000000 5000.000000000000 -21.676635700000 -4369.466310000000 0.000000000000 0.000000000000 -10817.588900000001 -21.676635700000 26985.859400000001 320.935913000000 -10074.344700000000 10817.588900000001 0.000000000000 -4369.466310000000 320.935913000000 30560.343799999999 911.798096000000 21.676635700000 4369.466310000000 0.000000000000 -10074.344700000000 911.798096000000 4807.875490000000 5 24 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13139.924800000001 301.898285000000 0.000000000000 5000.000000000000 0.000000000000 -13139.924800000001 0.000000000000 5296.580080000000 0.000000000000 0.000000000000 5000.000000000000 -301.898285000000 -5296.580080000000 0.000000000000 0.000000000000 -13139.924800000001 -301.898285000000 35761.648399999998 279.081635000000 -13990.005900000000 13139.924800000001 0.000000000000 -5296.580080000000 279.081635000000 41209.906300000002 756.642334000000 301.898285000000 5296.580080000000 0.000000000000 -13990.005900000000 756.642334000000 6457.427730000000 5 27 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9276.779300000000 -635.850647000000 0.000000000000 5000.000000000000 0.000000000000 -9276.779300000000 0.000000000000 -1563.921750000000 0.000000000000 0.000000000000 5000.000000000000 635.850647000000 1563.921750000000 0.000000000000 0.000000000000 -9276.779300000000 635.850647000000 19878.595700000002 -138.544830000000 3859.977540000000 9276.779300000000 0.000000000000 1563.921750000000 -138.544830000000 20909.914100000002 -519.903748000000 -635.850647000000 -1563.921750000000 0.000000000000 3859.977540000000 -519.903748000000 2335.375490000000 5 28 60 2727.000000000000 0.000000000000 0.000000000000 0.000000000000 5686.242680000000 -590.532898000000 0.000000000000 2727.000000000000 0.000000000000 -5686.242680000000 0.000000000000 -1915.102540000000 0.000000000000 0.000000000000 2727.000000000000 590.532898000000 1915.102540000000 0.000000000000 0.000000000000 -5686.242680000000 590.532898000000 13114.352500000001 418.192352000000 4483.694820000000 5686.242680000000 0.000000000000 1915.102540000000 418.192352000000 14479.354499999999 -1101.701290000000 -590.532898000000 -1915.102540000000 0.000000000000 4483.694820000000 -1101.701290000000 2109.735600000000 5 34 60 4250.000000000000 0.000000000000 0.000000000000 0.000000000000 5054.759770000000 -1368.428220000000 0.000000000000 4250.000000000000 0.000000000000 -5054.759770000000 0.000000000000 1222.189580000000 0.000000000000 0.000000000000 4250.000000000000 1368.428220000000 -1222.189580000000 0.000000000000 0.000000000000 -5054.759770000000 1368.428220000000 6592.536130000000 -357.963135000000 -1540.377690000000 5054.759770000000 0.000000000000 -1222.189580000000 -357.963135000000 7352.076660000000 -1581.886840000000 -1368.428220000000 1222.189580000000 0.000000000000 -1540.377690000000 -1581.886840000000 1677.260130000000 5 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11815.374000000000 1298.625850000000 0.000000000000 5000.000000000000 0.000000000000 -11815.374000000000 0.000000000000 3911.072510000000 0.000000000000 0.000000000000 5000.000000000000 -1298.625850000000 -3911.072510000000 0.000000000000 0.000000000000 -11815.374000000000 -1298.625850000000 29960.900399999999 962.307129000000 -9263.725590000000 11815.374000000000 0.000000000000 -3911.072510000000 962.307129000000 32772.910199999998 3528.813480000000 1298.625850000000 3911.072510000000 0.000000000000 -9263.725590000000 3528.813480000000 4851.814450000000 5 40 60 2582.000000000000 0.000000000000 0.000000000000 0.000000000000 6438.695310000000 924.353638000000 0.000000000000 2582.000000000000 0.000000000000 -6438.695310000000 0.000000000000 -2425.165530000000 0.000000000000 0.000000000000 2582.000000000000 -924.353638000000 2425.165530000000 0.000000000000 0.000000000000 -6438.695310000000 -924.353638000000 17478.252000000000 -859.824097000000 6113.260740000000 6438.695310000000 0.000000000000 2425.165530000000 -859.824097000000 18783.509800000000 2620.581050000000 924.353638000000 -2425.165530000000 0.000000000000 6113.260740000000 2620.581050000000 3427.048100000000 5 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12764.005900000000 1651.658450000000 0.000000000000 5000.000000000000 0.000000000000 -12764.005900000000 0.000000000000 -5287.194340000000 0.000000000000 0.000000000000 5000.000000000000 -1651.658450000000 5287.194340000000 0.000000000000 0.000000000000 -12764.005900000000 -1651.658450000000 34105.324200000003 -1872.057010000000 13604.377899999999 12764.005900000000 0.000000000000 5287.194340000000 -1872.057010000000 38567.183599999997 4442.411130000000 1651.658450000000 -5287.194340000000 0.000000000000 13604.377899999999 4442.411130000000 7220.537110000000 5 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12924.936500000000 2311.959470000000 0.000000000000 5000.000000000000 0.000000000000 -12924.936500000000 0.000000000000 -4962.777830000000 0.000000000000 0.000000000000 5000.000000000000 -2311.959470000000 4962.777830000000 0.000000000000 0.000000000000 -12924.936500000000 -2311.959470000000 35513.445299999999 -2363.528320000000 12908.959999999999 12924.936500000000 0.000000000000 4962.777830000000 -2363.528320000000 38707.777300000002 6191.823240000000 2311.959470000000 -4962.777830000000 0.000000000000 12908.959999999999 6191.823240000000 7152.328130000000 5 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12905.974600000000 2530.711910000000 0.000000000000 5000.000000000000 0.000000000000 -12905.974600000000 0.000000000000 -4956.838380000000 0.000000000000 0.000000000000 5000.000000000000 -2530.711910000000 4956.838380000000 0.000000000000 0.000000000000 -12905.974600000000 -2530.711910000000 35446.066400000003 -2553.890140000000 12864.193400000000 12905.974600000000 0.000000000000 4956.838380000000 -2553.890140000000 38628.738299999997 6743.790530000000 2530.711910000000 -4956.838380000000 0.000000000000 12864.193400000000 6743.790530000000 7188.825200000000 5 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12869.760700000001 2481.693600000000 0.000000000000 5000.000000000000 0.000000000000 -12869.760700000001 0.000000000000 -4784.133300000000 0.000000000000 0.000000000000 5000.000000000000 -2481.693600000000 4784.133300000000 0.000000000000 0.000000000000 -12869.760700000001 -2481.693600000000 35161.750000000000 -2419.187740000000 12379.353499999999 12869.760700000001 0.000000000000 4784.133300000000 -2419.187740000000 38175.500000000000 6595.824220000000 2481.693600000000 -4784.133300000000 0.000000000000 12379.353499999999 6595.824220000000 6817.300780000000 5 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12968.774400000000 2876.069090000000 0.000000000000 5000.000000000000 0.000000000000 -12968.774400000000 0.000000000000 -3850.705320000000 0.000000000000 0.000000000000 5000.000000000000 -2876.069090000000 3850.705320000000 0.000000000000 0.000000000000 -12968.774400000000 -2876.069090000000 35940.332000000002 -2123.041500000000 10069.609399999999 12968.774400000000 0.000000000000 3850.705320000000 -2123.041500000000 37732.863299999997 7621.657230000000 2876.069090000000 -3850.705320000000 0.000000000000 10069.609399999999 7621.657230000000 6132.156740000000 5 50 60 3344.000000000000 0.000000000000 0.000000000000 0.000000000000 8607.951170000000 1650.927610000000 0.000000000000 3344.000000000000 0.000000000000 -8607.951170000000 0.000000000000 943.459839000000 0.000000000000 0.000000000000 3344.000000000000 -1650.927610000000 -943.459839000000 0.000000000000 0.000000000000 -8607.951170000000 -1650.927610000000 23129.228500000001 476.069550000000 -2457.511720000000 8607.951170000000 0.000000000000 -943.459839000000 476.069550000000 23037.949199999999 4285.357420000000 1650.927610000000 943.459839000000 0.000000000000 -2457.511720000000 4285.357420000000 1739.130130000000 5 51 60 1789.000000000000 0.000000000000 0.000000000000 0.000000000000 4622.170410000000 881.409790000000 0.000000000000 1789.000000000000 0.000000000000 -4622.170410000000 0.000000000000 -80.759948700000 0.000000000000 0.000000000000 1789.000000000000 -881.409790000000 80.759948700000 0.000000000000 0.000000000000 -4622.170410000000 -881.409790000000 12433.554700000001 -41.764171600000 233.359772000000 4622.170410000000 0.000000000000 80.759948700000 -41.764171600000 12187.734399999999 2292.682130000000 881.409790000000 -80.759948700000 0.000000000000 233.359772000000 2292.682130000000 681.733704000000 5 52 60 4000.000000000000 0.000000000000 0.000000000000 0.000000000000 10273.603499999999 1931.882810000000 0.000000000000 4000.000000000000 0.000000000000 -10273.603499999999 0.000000000000 1571.776120000000 0.000000000000 0.000000000000 4000.000000000000 -1931.882810000000 -1571.776120000000 0.000000000000 0.000000000000 -10273.603499999999 -1931.882810000000 27517.619100000000 731.579712000000 -4042.025880000000 10273.603499999999 0.000000000000 -1571.776120000000 731.579712000000 27935.019499999999 5000.363770000000 1931.882810000000 1571.776120000000 0.000000000000 -4042.025880000000 5000.363770000000 2544.975590000000 5 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12667.449199999999 2358.864260000000 0.000000000000 5000.000000000000 0.000000000000 -12667.449199999999 0.000000000000 2742.484130000000 0.000000000000 0.000000000000 5000.000000000000 -2358.864260000000 -2742.484130000000 0.000000000000 0.000000000000 -12667.449199999999 -2358.864260000000 33670.546900000001 1211.841310000000 -6900.138670000000 12667.449199999999 0.000000000000 -2742.484130000000 1211.841310000000 35143.554700000001 6099.033690000000 2358.864260000000 2742.484130000000 0.000000000000 -6900.138670000000 6099.033690000000 4261.882810000000 5 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10476.262699999999 673.039001000000 0.000000000000 5000.000000000000 0.000000000000 -10476.262699999999 0.000000000000 3843.280520000000 0.000000000000 0.000000000000 5000.000000000000 -673.039001000000 -3843.280520000000 0.000000000000 0.000000000000 -10476.262699999999 -673.039001000000 24693.130900000000 764.314331000000 -8361.511720000000 10476.262699999999 0.000000000000 -3843.280520000000 764.314331000000 27329.521499999999 2385.036130000000 673.039001000000 3843.280520000000 0.000000000000 -8361.511720000000 2385.036130000000 4447.028320000000 5 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8550.016600000001 -999.524597000000 0.000000000000 5000.000000000000 0.000000000000 -8550.016600000001 0.000000000000 3860.597900000000 0.000000000000 0.000000000000 5000.000000000000 999.524597000000 -3860.597900000000 0.000000000000 0.000000000000 -8550.016600000001 999.524597000000 17556.107400000001 -452.874969000000 -7924.193850000000 8550.016600000001 0.000000000000 -3860.597900000000 -452.874969000000 21109.373000000000 -1196.949710000000 -999.524597000000 3860.597900000000 0.000000000000 -7924.193850000000 -1196.949710000000 4443.185060000000 5 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6038.250980000000 -1606.969600000000 0.000000000000 5000.000000000000 0.000000000000 -6038.250980000000 0.000000000000 1780.218630000000 0.000000000000 0.000000000000 5000.000000000000 1606.969600000000 -1780.218630000000 0.000000000000 0.000000000000 -6038.250980000000 1606.969600000000 8131.605960000000 -533.241638000000 -2264.977540000000 6038.250980000000 0.000000000000 -1780.218630000000 -533.241638000000 8765.736330000000 -1865.313840000000 -1606.969600000000 1780.218630000000 0.000000000000 -2264.977540000000 -1865.313840000000 1719.880250000000 5 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7275.483400000000 -1340.569090000000 0.000000000000 5000.000000000000 0.000000000000 -7275.483400000000 0.000000000000 2128.685300000000 0.000000000000 0.000000000000 5000.000000000000 1340.569090000000 -2128.685300000000 0.000000000000 0.000000000000 -7275.483400000000 1340.569090000000 12406.703100000001 -500.920135000000 -3426.835690000000 7275.483400000000 0.000000000000 -2128.685300000000 -500.920135000000 13539.574199999999 -1679.084470000000 -1340.569090000000 2128.685300000000 0.000000000000 -3426.835690000000 -1679.084470000000 2028.207640000000 5 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9465.864260000000 -783.924133000000 0.000000000000 5000.000000000000 0.000000000000 -9465.864260000000 0.000000000000 1130.412480000000 0.000000000000 0.000000000000 5000.000000000000 783.924133000000 -1130.412480000000 0.000000000000 0.000000000000 -9465.864260000000 783.924133000000 19781.218799999999 -330.703827000000 -1753.772580000000 9465.864260000000 0.000000000000 -1130.412480000000 -330.703827000000 20736.910199999998 -1185.212770000000 -783.924133000000 1130.412480000000 0.000000000000 -1753.772580000000 -1185.212770000000 1484.465700000000 6 13 60 4044.000000000000 0.000000000000 0.000000000000 0.000000000000 9687.753909999999 1980.911010000000 0.000000000000 4044.000000000000 0.000000000000 -9687.753909999999 0.000000000000 -4135.395510000000 0.000000000000 0.000000000000 4044.000000000000 -1980.911010000000 4135.395510000000 0.000000000000 0.000000000000 -9687.753909999999 -1980.911010000000 24859.484400000001 -2050.680910000000 10009.163100000000 9687.753909999999 0.000000000000 4135.395510000000 -2050.680910000000 27998.865200000000 4976.793950000000 1980.911010000000 -4135.395510000000 0.000000000000 10009.163100000000 4976.793950000000 5698.465820000000 6 14 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11549.401400000001 1771.553830000000 0.000000000000 5000.000000000000 0.000000000000 -11549.401400000001 0.000000000000 -3582.184330000000 0.000000000000 0.000000000000 5000.000000000000 -1771.553830000000 3582.184330000000 0.000000000000 0.000000000000 -11549.401400000001 -1771.553830000000 28068.158200000002 -1481.931760000000 8505.575199999999 11549.401400000001 0.000000000000 3582.184330000000 -1481.931760000000 30575.259800000000 4327.713380000000 1771.553830000000 -3582.184330000000 0.000000000000 8505.575199999999 4327.713380000000 4325.891600000000 6 22 60 3547.000000000000 0.000000000000 0.000000000000 0.000000000000 7026.928220000000 770.194824000000 0.000000000000 3547.000000000000 0.000000000000 -7026.928220000000 0.000000000000 3959.747070000000 0.000000000000 0.000000000000 3547.000000000000 -770.194824000000 -3959.747070000000 0.000000000000 0.000000000000 -7026.928220000000 -770.194824000000 16679.357400000001 1156.047490000000 -8499.937500000000 7026.928220000000 0.000000000000 -3959.747070000000 1156.047490000000 20628.712899999999 2334.942140000000 770.194824000000 3959.747070000000 0.000000000000 -8499.937500000000 2334.942140000000 5380.231930000000 6 27 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8988.298830000000 933.636902000000 0.000000000000 5000.000000000000 0.000000000000 -8988.298830000000 0.000000000000 -2916.562010000000 0.000000000000 0.000000000000 5000.000000000000 -933.636902000000 2916.562010000000 0.000000000000 0.000000000000 -8988.298830000000 -933.636902000000 19028.267599999999 -1110.956670000000 6236.532230000000 8988.298830000000 0.000000000000 2916.562010000000 -1110.956670000000 20747.218799999999 2649.037350000000 933.636902000000 -2916.562010000000 0.000000000000 6236.532230000000 2649.037350000000 3470.623780000000 6 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5844.982420000000 -671.753784000000 0.000000000000 5000.000000000000 0.000000000000 -5844.982420000000 0.000000000000 902.236328000000 0.000000000000 0.000000000000 5000.000000000000 671.753784000000 -902.236328000000 0.000000000000 0.000000000000 -5844.982420000000 671.753784000000 7331.554690000000 -148.294159000000 -1131.668210000000 5844.982420000000 0.000000000000 -902.236328000000 -148.294159000000 8429.306640000001 -642.581360000000 -671.753784000000 902.236328000000 0.000000000000 -1131.668210000000 -642.581360000000 1412.590580000000 6 42 60 2473.000000000000 0.000000000000 0.000000000000 0.000000000000 6098.935550000000 1216.941040000000 0.000000000000 2473.000000000000 0.000000000000 -6098.935550000000 0.000000000000 -2841.204590000000 0.000000000000 0.000000000000 2473.000000000000 -1216.941040000000 2841.204590000000 0.000000000000 0.000000000000 -6098.935550000000 -1216.941040000000 15891.479499999999 -1412.831670000000 7013.864260000000 6098.935550000000 0.000000000000 2841.204590000000 -1412.831670000000 18387.869100000000 3068.259520000000 1216.941040000000 -2841.204590000000 0.000000000000 7013.864260000000 3068.259520000000 4099.659180000000 6 44 60 1464.000000000000 0.000000000000 0.000000000000 0.000000000000 3687.711910000000 1045.301270000000 0.000000000000 1464.000000000000 0.000000000000 -3687.711910000000 0.000000000000 -1626.668820000000 0.000000000000 0.000000000000 1464.000000000000 -1045.301270000000 1626.668820000000 0.000000000000 0.000000000000 -3687.711910000000 -1045.301270000000 10156.887699999999 -1153.445070000000 4091.079350000000 3687.711910000000 0.000000000000 1626.668820000000 -1153.445070000000 11181.257799999999 2677.310790000000 1045.301270000000 -1626.668820000000 0.000000000000 4091.079350000000 2677.310790000000 2674.533940000000 6 45 60 2616.000000000000 0.000000000000 0.000000000000 0.000000000000 6371.844730000000 1734.247800000000 0.000000000000 2616.000000000000 0.000000000000 -6371.844730000000 0.000000000000 -2355.048830000000 0.000000000000 0.000000000000 2616.000000000000 -1734.247800000000 2355.048830000000 0.000000000000 0.000000000000 -6371.844730000000 -1734.247800000000 16863.632799999999 -1565.850950000000 5751.140140000000 6371.844730000000 0.000000000000 2355.048830000000 -1565.850950000000 17940.326200000000 4302.525880000000 1734.247800000000 -2355.048830000000 0.000000000000 5751.140140000000 4302.525880000000 3622.341800000000 6 46 60 3088.000000000000 0.000000000000 0.000000000000 0.000000000000 7603.926760000000 2210.724610000000 0.000000000000 3088.000000000000 0.000000000000 -7603.926760000000 0.000000000000 -2028.721310000000 0.000000000000 0.000000000000 3088.000000000000 -2210.724610000000 2028.721310000000 0.000000000000 0.000000000000 -7603.926760000000 -2210.724610000000 20494.640599999999 -1416.085940000000 4986.781250000000 7603.926760000000 0.000000000000 2028.721310000000 -1416.085940000000 20765.818400000000 5516.737300000000 2210.724610000000 -2028.721310000000 0.000000000000 4986.781250000000 5516.737300000000 3683.919920000000 6 47 60 3071.000000000000 0.000000000000 0.000000000000 0.000000000000 7693.956540000000 2277.014650000000 0.000000000000 3071.000000000000 0.000000000000 -7693.956540000000 0.000000000000 -833.518860000000 0.000000000000 0.000000000000 3071.000000000000 -2277.014650000000 833.518860000000 0.000000000000 0.000000000000 -7693.956540000000 -2277.014650000000 21146.236300000000 -699.720154000000 2066.933590000000 7693.956540000000 0.000000000000 833.518860000000 -699.720154000000 20704.468799999999 5754.195800000000 2277.014650000000 -833.518860000000 0.000000000000 2066.933590000000 5754.195800000000 3163.009770000000 6 48 60 3926.000000000000 0.000000000000 0.000000000000 0.000000000000 9831.304690000001 2236.368650000000 0.000000000000 3926.000000000000 0.000000000000 -9831.304690000001 0.000000000000 1012.139590000000 0.000000000000 0.000000000000 3926.000000000000 -2236.368650000000 -1012.139590000000 0.000000000000 0.000000000000 -9831.304690000001 -2236.368650000000 26277.978500000001 308.710785000000 -2740.534180000000 9831.304690000001 0.000000000000 -1012.139590000000 308.710785000000 26219.472699999998 5600.115720000000 2236.368650000000 1012.139590000000 0.000000000000 -2740.534180000000 5600.115720000000 2983.107180000000 6 50 60 2645.000000000000 0.000000000000 0.000000000000 0.000000000000 6531.755370000000 1618.436890000000 0.000000000000 2645.000000000000 0.000000000000 -6531.755370000000 0.000000000000 -132.391098000000 0.000000000000 0.000000000000 2645.000000000000 -1618.436890000000 132.391098000000 0.000000000000 0.000000000000 -6531.755370000000 -1618.436890000000 17334.611300000000 -118.439606000000 273.545959000000 6531.755370000000 0.000000000000 132.391098000000 -118.439606000000 16707.681600000000 4054.931640000000 1618.436890000000 -132.391098000000 0.000000000000 273.545959000000 4054.931640000000 1618.791260000000 6 51 60 1789.000000000000 0.000000000000 0.000000000000 0.000000000000 4441.910640000000 1216.998660000000 0.000000000000 1789.000000000000 0.000000000000 -4441.910640000000 0.000000000000 -717.838501000000 0.000000000000 0.000000000000 1789.000000000000 -1216.998660000000 717.838501000000 0.000000000000 0.000000000000 -4441.910640000000 -1216.998660000000 11982.567400000000 -515.908203000000 1813.412600000000 4441.910640000000 0.000000000000 717.838501000000 -515.908203000000 11563.675800000001 3068.685550000000 1216.998660000000 -717.838501000000 0.000000000000 1813.412600000000 3068.685550000000 1402.170290000000 6 52 60 3107.000000000000 0.000000000000 0.000000000000 0.000000000000 7639.969730000000 1873.130250000000 0.000000000000 3107.000000000000 0.000000000000 -7639.969730000000 0.000000000000 -27.065845500000 0.000000000000 0.000000000000 3107.000000000000 -1873.130250000000 27.065845500000 0.000000000000 0.000000000000 -7639.969730000000 -1873.130250000000 20141.603500000001 -34.196949000000 -7.404050830000 7639.969730000000 0.000000000000 27.065845500000 -34.196949000000 19588.992200000001 4665.094730000000 1873.130250000000 -27.065845500000 0.000000000000 -7.404050830000 4665.094730000000 1986.706540000000 6 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8007.914060000000 -43.324832900000 0.000000000000 5000.000000000000 0.000000000000 -8007.914060000000 0.000000000000 2114.563960000000 0.000000000000 0.000000000000 5000.000000000000 43.324832900000 -2114.563960000000 0.000000000000 0.000000000000 -8007.914060000000 43.324832900000 15351.794900000001 356.591461000000 -4622.762700000000 8007.914060000000 0.000000000000 -2114.563960000000 356.591461000000 17251.269499999999 572.933777000000 -43.324832900000 2114.563960000000 0.000000000000 -4622.762700000000 572.933777000000 2460.464360000000 6 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5895.254880000000 -666.289856000000 0.000000000000 5000.000000000000 0.000000000000 -5895.254880000000 0.000000000000 796.511108000000 0.000000000000 0.000000000000 5000.000000000000 666.289856000000 -796.511108000000 0.000000000000 0.000000000000 -5895.254880000000 666.289856000000 7631.302730000000 -53.382949800000 -1163.703490000000 5895.254880000000 0.000000000000 -796.511108000000 -53.382949800000 8369.387699999999 -592.080261000000 -666.289856000000 796.511108000000 0.000000000000 -1163.703490000000 -592.080261000000 1086.669920000000 6 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5754.874020000000 -733.936340000000 0.000000000000 5000.000000000000 0.000000000000 -5754.874020000000 0.000000000000 422.369720000000 0.000000000000 0.000000000000 5000.000000000000 733.936340000000 -422.369720000000 0.000000000000 0.000000000000 -5754.874020000000 733.936340000000 7225.559570000000 -95.584434500000 -497.790680000000 5754.874020000000 0.000000000000 -422.369720000000 -95.584434500000 7715.434570000000 -704.752686000000 -733.936340000000 422.369720000000 0.000000000000 -497.790680000000 -704.752686000000 814.635986000000 6 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7347.371580000000 -304.693756000000 0.000000000000 5000.000000000000 0.000000000000 -7347.371580000000 0.000000000000 919.166931000000 0.000000000000 0.000000000000 5000.000000000000 304.693756000000 -919.166931000000 0.000000000000 0.000000000000 -7347.371580000000 304.693756000000 12834.226600000000 -34.816452000000 -1772.475950000000 7347.371580000000 0.000000000000 -919.166931000000 -34.816452000000 13733.130900000000 16.470790900000 -304.693756000000 919.166931000000 0.000000000000 -1772.475950000000 16.470790900000 1280.576540000000 7 12 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12358.913100000000 2768.464360000000 0.000000000000 5000.000000000000 0.000000000000 -12358.913100000000 0.000000000000 -4269.395510000000 0.000000000000 0.000000000000 5000.000000000000 -2768.464360000000 4269.395510000000 0.000000000000 0.000000000000 -12358.913100000000 -2768.464360000000 32984.003900000003 -2465.501710000000 10757.369100000000 12358.913100000000 0.000000000000 4269.395510000000 -2465.501710000000 35293.800799999997 7144.197750000000 2768.464360000000 -4269.395510000000 0.000000000000 10757.369100000000 7144.197750000000 6137.278810000000 7 13 60 3286.000000000000 0.000000000000 0.000000000000 0.000000000000 8600.781250000000 2052.248290000000 0.000000000000 3286.000000000000 0.000000000000 -8600.781250000000 0.000000000000 -3751.123050000000 0.000000000000 0.000000000000 3286.000000000000 -2052.248290000000 3751.123050000000 0.000000000000 0.000000000000 -8600.781250000000 -2052.248290000000 24082.115200000000 -2366.935790000000 9861.866210000000 8600.781250000000 0.000000000000 3751.123050000000 -2366.935790000000 27004.283200000002 5463.227050000000 2052.248290000000 -3751.123050000000 0.000000000000 9861.866210000000 5463.227050000000 5885.850590000000 7 14 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12394.443400000000 2292.796630000000 0.000000000000 5000.000000000000 0.000000000000 -12394.443400000000 0.000000000000 -3783.685550000000 0.000000000000 0.000000000000 5000.000000000000 -2292.796630000000 3783.685550000000 0.000000000000 0.000000000000 -12394.443400000000 -2292.796630000000 32297.804700000001 -1907.528560000000 9557.416990000000 12394.443400000000 0.000000000000 3783.685550000000 -1907.528560000000 34580.500000000000 5826.958010000000 2292.796630000000 -3783.685550000000 0.000000000000 9557.416990000000 5826.958010000000 4828.213870000000 7 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8554.879880000000 634.667419000000 0.000000000000 5000.000000000000 0.000000000000 -8554.879880000000 0.000000000000 4369.652830000000 0.000000000000 0.000000000000 5000.000000000000 -634.667419000000 -4369.652830000000 0.000000000000 0.000000000000 -8554.879880000000 -634.667419000000 18676.353500000001 1062.368290000000 -8577.332030000000 8554.879880000000 0.000000000000 -4369.652830000000 1062.368290000000 22204.302700000000 2380.862790000000 634.667419000000 4369.652830000000 0.000000000000 -8577.332030000000 2380.862790000000 5229.499510000000 7 23 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10164.689500000000 1053.130370000000 0.000000000000 5000.000000000000 0.000000000000 -10164.689500000000 0.000000000000 5268.569340000000 0.000000000000 0.000000000000 5000.000000000000 -1053.130370000000 -5268.569340000000 0.000000000000 0.000000000000 -10164.689500000000 -1053.130370000000 24431.675800000001 1441.599370000000 -11603.361300000000 10164.689500000000 0.000000000000 -5268.569340000000 1441.599370000000 29517.132799999999 3139.296140000000 1053.130370000000 5268.569340000000 0.000000000000 -11603.361300000000 3139.296140000000 6809.541020000000 7 27 60 3860.000000000000 0.000000000000 0.000000000000 0.000000000000 7334.712400000000 951.938232000000 0.000000000000 3860.000000000000 0.000000000000 -7334.712400000000 0.000000000000 -2353.392820000000 0.000000000000 0.000000000000 3860.000000000000 -951.938232000000 2353.392820000000 0.000000000000 0.000000000000 -7334.712400000000 -951.938232000000 15918.393599999999 -833.430603000000 4952.124020000000 7334.712400000000 0.000000000000 2353.392820000000 -833.430603000000 17215.398399999998 2409.854490000000 951.938232000000 -2353.392820000000 0.000000000000 4952.124020000000 2409.854490000000 2541.546880000000 7 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6124.892580000000 -317.999481000000 0.000000000000 5000.000000000000 0.000000000000 -6124.892580000000 0.000000000000 740.408081000000 0.000000000000 0.000000000000 5000.000000000000 317.999481000000 -740.408081000000 0.000000000000 0.000000000000 -6124.892580000000 317.999481000000 8014.451660000000 -177.532318000000 -704.647217000000 6124.892580000000 0.000000000000 -740.408081000000 -177.532318000000 9141.966800000000 -202.077194000000 -317.999481000000 740.408081000000 0.000000000000 -704.647217000000 -202.077194000000 1356.393800000000 7 46 60 2435.000000000000 0.000000000000 0.000000000000 0.000000000000 6325.526370000000 1988.837280000000 0.000000000000 2435.000000000000 0.000000000000 -6325.526370000000 0.000000000000 -1910.561520000000 0.000000000000 0.000000000000 2435.000000000000 -1988.837280000000 1910.561520000000 0.000000000000 0.000000000000 -6325.526370000000 -1988.837280000000 18216.525399999999 -1532.355220000000 4986.804690000000 6325.526370000000 0.000000000000 1910.561520000000 -1532.355220000000 18333.851600000002 5231.412600000000 1988.837280000000 -1910.561520000000 0.000000000000 4986.804690000000 5231.412600000000 3559.324710000000 7 47 60 2161.000000000000 0.000000000000 0.000000000000 0.000000000000 5646.610840000000 1830.233520000000 0.000000000000 2161.000000000000 0.000000000000 -5646.610840000000 0.000000000000 -887.121155000000 0.000000000000 0.000000000000 2161.000000000000 -1830.233520000000 887.121155000000 0.000000000000 0.000000000000 -5646.610840000000 -1830.233520000000 16445.091799999998 -789.424927000000 2335.574460000000 5646.610840000000 0.000000000000 887.121155000000 -789.424927000000 15697.892599999999 4828.740720000000 1830.233520000000 -887.121155000000 0.000000000000 2335.574460000000 4828.740720000000 2528.224610000000 7 48 60 2613.000000000000 0.000000000000 0.000000000000 0.000000000000 6740.811040000000 1946.490600000000 0.000000000000 2613.000000000000 0.000000000000 -6740.811040000000 0.000000000000 -422.482849000000 0.000000000000 0.000000000000 2613.000000000000 -1946.490600000000 422.482849000000 0.000000000000 0.000000000000 -6740.811040000000 -1946.490600000000 19059.855500000001 -427.636047000000 1039.333860000000 6740.811040000000 0.000000000000 422.482849000000 -427.636047000000 18206.589800000002 5052.606450000000 1946.490600000000 -422.482849000000 0.000000000000 1039.333860000000 5052.606450000000 2346.816890000000 7 49 60 3594.000000000000 0.000000000000 0.000000000000 0.000000000000 9379.002930000001 2021.465210000000 0.000000000000 3594.000000000000 0.000000000000 -9379.002930000001 0.000000000000 1070.313720000000 0.000000000000 0.000000000000 3594.000000000000 -2021.465210000000 -1070.313720000000 0.000000000000 0.000000000000 -9379.002930000001 -2021.465210000000 26046.076200000000 35.070560500000 -3024.320560000000 9379.002930000001 0.000000000000 -1070.313720000000 35.070560500000 26850.355500000001 5221.970700000000 2021.465210000000 1070.313720000000 0.000000000000 -3024.320560000000 5221.970700000000 3744.686280000000 7 50 60 3196.000000000000 0.000000000000 0.000000000000 0.000000000000 8252.812500000000 2127.591800000000 0.000000000000 3196.000000000000 0.000000000000 -8252.812500000000 0.000000000000 -522.051392000000 0.000000000000 0.000000000000 3196.000000000000 -2127.591800000000 522.051392000000 0.000000000000 0.000000000000 -8252.812500000000 -2127.591800000000 22965.470700000002 -486.386536000000 1200.865840000000 8252.812500000000 0.000000000000 522.051392000000 -486.386536000000 22437.699199999999 5522.333010000000 2127.591800000000 -522.051392000000 0.000000000000 1200.865840000000 5522.333010000000 2590.872560000000 7 51 60 1808.000000000000 0.000000000000 0.000000000000 0.000000000000 4677.337400000000 1386.538570000000 0.000000000000 1808.000000000000 0.000000000000 -4677.337400000000 0.000000000000 -1256.338380000000 0.000000000000 0.000000000000 1808.000000000000 -1386.538570000000 1256.338380000000 0.000000000000 0.000000000000 -4677.337400000000 -1386.538570000000 13309.654300000000 -1002.305240000000 3293.139400000000 4677.337400000000 0.000000000000 1256.338380000000 -1002.305240000000 13166.860400000000 3643.321530000000 1386.538570000000 -1256.338380000000 0.000000000000 3293.139400000000 3643.321530000000 2177.596190000000 7 52 60 3735.000000000000 0.000000000000 0.000000000000 0.000000000000 9646.127930000001 2417.382570000000 0.000000000000 3735.000000000000 0.000000000000 -9646.127930000001 0.000000000000 -421.633972000000 0.000000000000 0.000000000000 3735.000000000000 -2417.382570000000 421.633972000000 0.000000000000 0.000000000000 -9646.127930000001 -2417.382570000000 26755.230500000001 -468.820221000000 909.796570000000 9646.127930000001 0.000000000000 421.633972000000 -468.820221000000 26330.623000000000 6262.322270000000 2417.382570000000 -421.633972000000 0.000000000000 909.796570000000 6262.322270000000 3045.531980000000 7 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6435.126950000000 -194.705154000000 0.000000000000 5000.000000000000 0.000000000000 -6435.126950000000 0.000000000000 569.019775000000 0.000000000000 0.000000000000 5000.000000000000 194.705154000000 -569.019775000000 0.000000000000 0.000000000000 -6435.126950000000 194.705154000000 9369.077149999999 83.600662200000 -1114.528080000000 6435.126950000000 0.000000000000 -569.019775000000 83.600662200000 10785.061500000000 115.475777000000 -194.705154000000 569.019775000000 0.000000000000 -1114.528080000000 115.475777000000 1771.041020000000 7 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5878.883300000000 -426.400787000000 0.000000000000 5000.000000000000 0.000000000000 -5878.883300000000 0.000000000000 168.371429000000 0.000000000000 0.000000000000 5000.000000000000 426.400787000000 -168.371429000000 0.000000000000 0.000000000000 -5878.883300000000 426.400787000000 7434.024410000000 -158.618347000000 28.763870200000 5878.883300000000 0.000000000000 -168.371429000000 -158.618347000000 8492.894530000000 -325.425507000000 -426.400787000000 168.371429000000 0.000000000000 28.763870200000 -325.425507000000 1298.794920000000 8 10 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11235.772499999999 4409.854980000000 0.000000000000 5000.000000000000 0.000000000000 -11235.772499999999 0.000000000000 -3075.863280000000 0.000000000000 0.000000000000 5000.000000000000 -4409.854980000000 3075.863280000000 0.000000000000 0.000000000000 -11235.772499999999 -4409.854980000000 31513.625000000000 -2779.389650000000 6986.292480000000 11235.772499999999 0.000000000000 3075.863280000000 -2779.389650000000 28855.722699999998 10660.193400000000 4409.854980000000 -3075.863280000000 0.000000000000 6986.292480000000 10660.193400000000 7387.377440000000 8 11 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12120.965800000000 5043.425290000000 0.000000000000 5000.000000000000 0.000000000000 -12120.965800000000 0.000000000000 -3436.639650000000 0.000000000000 0.000000000000 5000.000000000000 -5043.425290000000 3436.639650000000 0.000000000000 0.000000000000 -12120.965800000000 -5043.425290000000 35893.558599999997 -3561.521240000000 8253.932620000000 12120.965800000000 0.000000000000 3436.639650000000 -3561.521240000000 32776.683599999997 12438.170899999999 5043.425290000000 -3436.639650000000 0.000000000000 8253.932620000000 12438.170899999999 8620.418949999999 8 15 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12489.773400000000 3588.224370000000 0.000000000000 5000.000000000000 0.000000000000 -12489.773400000000 0.000000000000 -2884.417720000000 0.000000000000 0.000000000000 5000.000000000000 -3588.224370000000 2884.417720000000 0.000000000000 0.000000000000 -12489.773400000000 -3588.224370000000 34801.585899999998 -2022.633420000000 6828.389160000000 12489.773400000000 0.000000000000 2884.417720000000 -2022.633420000000 34251.878900000003 9067.804690000001 3588.224370000000 -2884.417720000000 0.000000000000 6828.389160000000 9067.804690000001 5309.811040000000 8 26 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11368.061500000000 3972.239260000000 0.000000000000 5000.000000000000 0.000000000000 -11368.061500000000 0.000000000000 -3089.324710000000 0.000000000000 0.000000000000 5000.000000000000 -3972.239260000000 3089.324710000000 0.000000000000 0.000000000000 -11368.061500000000 -3972.239260000000 30999.689500000000 -2514.947020000000 7106.239260000000 11368.061500000000 0.000000000000 3089.324710000000 -2514.947020000000 29414.892599999999 9542.860350000001 3972.239260000000 -3089.324710000000 0.000000000000 7106.239260000000 9542.860350000001 6551.660640000000 8 34 60 4516.000000000000 0.000000000000 0.000000000000 0.000000000000 5390.454590000000 148.950287000000 0.000000000000 4516.000000000000 0.000000000000 -5390.454590000000 0.000000000000 -145.915787000000 0.000000000000 0.000000000000 4516.000000000000 -148.950287000000 145.915787000000 0.000000000000 0.000000000000 -5390.454590000000 -148.950287000000 6849.116700000000 -94.572471600000 178.139267000000 5390.454590000000 0.000000000000 145.915787000000 -94.572471600000 7238.162110000000 349.742462000000 148.950287000000 -145.915787000000 0.000000000000 178.139267000000 349.742462000000 647.018677000000 8 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11607.374000000000 2236.432130000000 0.000000000000 5000.000000000000 0.000000000000 -11607.374000000000 0.000000000000 -899.771729000000 0.000000000000 0.000000000000 5000.000000000000 -2236.432130000000 899.771729000000 0.000000000000 0.000000000000 -11607.374000000000 -2236.432130000000 30558.236300000000 -383.074677000000 1334.156250000000 11607.374000000000 0.000000000000 899.771729000000 -383.074677000000 30819.671900000001 5762.810060000000 2236.432130000000 -899.771729000000 0.000000000000 1334.156250000000 5762.810060000000 2861.001460000000 8 48 60 4575.000000000000 0.000000000000 0.000000000000 0.000000000000 11372.927700000000 5183.908690000000 0.000000000000 4575.000000000000 0.000000000000 -11372.927700000000 0.000000000000 -2395.135500000000 0.000000000000 0.000000000000 4575.000000000000 -5183.908690000000 2395.135500000000 0.000000000000 0.000000000000 -11372.927700000000 -5183.908690000000 34800.332000000002 -3088.183840000000 5665.205570000000 11372.927700000000 0.000000000000 2395.135500000000 -3088.183840000000 30649.300800000001 12699.700199999999 5183.908690000000 -2395.135500000000 0.000000000000 5665.205570000000 12699.700199999999 8516.236330000000 8 49 60 4825.000000000000 0.000000000000 0.000000000000 0.000000000000 12050.182600000000 5094.892090000000 0.000000000000 4825.000000000000 0.000000000000 -12050.182600000000 0.000000000000 -1957.963750000000 0.000000000000 0.000000000000 4825.000000000000 -5094.892090000000 1957.963750000000 0.000000000000 0.000000000000 -12050.182600000000 -5094.892090000000 36343.835899999998 -2680.480710000000 4505.006350000000 12050.182600000000 0.000000000000 1957.963750000000 -2680.480710000000 32457.382799999999 12442.291999999999 5094.892090000000 -1957.963750000000 0.000000000000 4505.006350000000 12442.291999999999 8112.562990000000 8 50 60 2899.000000000000 0.000000000000 0.000000000000 0.000000000000 7174.064940000000 3457.879880000000 0.000000000000 2899.000000000000 0.000000000000 -7174.064940000000 0.000000000000 -1935.982910000000 0.000000000000 0.000000000000 2899.000000000000 -3457.879880000000 1935.982910000000 0.000000000000 0.000000000000 -7174.064940000000 -3457.879880000000 22112.232400000001 -2474.381840000000 4657.821780000000 7174.064940000000 0.000000000000 1935.982910000000 -2474.381840000000 19620.716799999998 8505.993160000000 3457.879880000000 -1935.982910000000 0.000000000000 4657.821780000000 8505.993160000000 6075.107910000000 8 52 60 3830.000000000000 0.000000000000 0.000000000000 0.000000000000 9546.900390000001 4232.171390000000 0.000000000000 3830.000000000000 0.000000000000 -9546.900390000001 0.000000000000 -1962.005370000000 0.000000000000 0.000000000000 3830.000000000000 -4232.171390000000 1962.005370000000 0.000000000000 0.000000000000 -9546.900390000001 -4232.171390000000 28887.353500000001 -2474.945560000000 4698.896970000000 9546.900390000001 0.000000000000 1962.005370000000 -2474.945560000000 25702.912100000001 10443.396500000001 4232.171390000000 -1962.005370000000 0.000000000000 4698.896970000000 10443.396500000001 6744.676270000000 8 56 60 4547.000000000000 0.000000000000 0.000000000000 0.000000000000 7689.453130000000 582.578491000000 0.000000000000 4547.000000000000 0.000000000000 -7689.453130000000 0.000000000000 1244.793460000000 0.000000000000 0.000000000000 4547.000000000000 -582.578491000000 -1244.793460000000 0.000000000000 0.000000000000 -7689.453130000000 -582.578491000000 15931.219700000000 211.987045000000 -3036.851560000000 7689.453130000000 0.000000000000 -1244.793460000000 211.987045000000 16884.087899999999 1476.636840000000 582.578491000000 1244.793460000000 0.000000000000 -3036.851560000000 1476.636840000000 1730.855470000000 8 57 60 4053.000000000000 0.000000000000 0.000000000000 0.000000000000 5943.747560000000 55.242580400000 0.000000000000 4053.000000000000 0.000000000000 -5943.747560000000 0.000000000000 1036.925900000000 0.000000000000 0.000000000000 4053.000000000000 -55.242580400000 -1036.925900000000 0.000000000000 0.000000000000 -5943.747560000000 -55.242580400000 10531.703100000001 -72.407104500000 -2187.323730000000 5943.747560000000 0.000000000000 -1036.925900000000 -72.407104500000 12005.973599999999 304.248352000000 55.242580400000 1036.925900000000 0.000000000000 -2187.323730000000 304.248352000000 1715.386720000000 9 12 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11165.067400000000 1937.052250000000 0.000000000000 5000.000000000000 0.000000000000 -11165.067400000000 0.000000000000 -5907.044920000000 0.000000000000 0.000000000000 5000.000000000000 -1937.052250000000 5907.044920000000 0.000000000000 0.000000000000 -11165.067400000000 -1937.052250000000 27211.250000000000 -2260.325440000000 13124.305700000001 11165.067400000000 0.000000000000 5907.044920000000 -2260.325440000000 33015.777300000002 4827.896000000000 1937.052250000000 -5907.044920000000 0.000000000000 13124.305700000001 4827.896000000000 8512.334960000000 9 15 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11280.926799999999 517.166565000000 0.000000000000 5000.000000000000 0.000000000000 -11280.926799999999 0.000000000000 -4000.015630000000 0.000000000000 0.000000000000 5000.000000000000 -517.166565000000 4000.015630000000 0.000000000000 0.000000000000 -11280.926799999999 -517.166565000000 27382.349600000001 -623.342590000000 8351.691409999999 11280.926799999999 0.000000000000 4000.015630000000 -623.342590000000 31252.168000000001 1327.990480000000 517.166565000000 -4000.015630000000 0.000000000000 8351.691409999999 1327.990480000000 4571.251950000000 9 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12709.197300000000 205.076401000000 0.000000000000 5000.000000000000 0.000000000000 -12709.197300000000 0.000000000000 3273.638180000000 0.000000000000 0.000000000000 5000.000000000000 -205.076401000000 -3273.638180000000 0.000000000000 0.000000000000 -12709.197300000000 -205.076401000000 33356.375000000000 187.797485000000 -8400.863280000000 12709.197300000000 0.000000000000 -3273.638180000000 187.797485000000 35377.003900000003 454.341003000000 205.076401000000 3273.638180000000 0.000000000000 -8400.863280000000 454.341003000000 3144.733400000000 9 23 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12821.145500000001 -139.051804000000 0.000000000000 5000.000000000000 0.000000000000 -12821.145500000001 0.000000000000 3471.837650000000 0.000000000000 0.000000000000 5000.000000000000 139.051804000000 -3471.837650000000 0.000000000000 0.000000000000 -12821.145500000001 139.051804000000 33892.777300000002 -120.973656000000 -8956.166020000001 12821.145500000001 0.000000000000 -3471.837650000000 -120.973656000000 36121.722699999998 -535.550842000000 -139.051804000000 3471.837650000000 0.000000000000 -8956.166020000001 -535.550842000000 3427.391360000000 9 27 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8202.519530000000 -113.739365000000 0.000000000000 5000.000000000000 0.000000000000 -8202.519530000000 0.000000000000 -5307.515140000000 0.000000000000 0.000000000000 5000.000000000000 113.739365000000 5307.515140000000 0.000000000000 0.000000000000 -8202.519530000000 113.739365000000 15277.620100000000 -11.690577500000 8774.781250000000 8202.519530000000 0.000000000000 5307.515140000000 -11.690577500000 20954.955099999999 238.749237000000 -113.739365000000 -5307.515140000000 0.000000000000 8774.781250000000 238.749237000000 6269.085450000000 9 34 60 4042.000000000000 0.000000000000 0.000000000000 0.000000000000 5307.056640000000 -642.837402000000 0.000000000000 4042.000000000000 0.000000000000 -5307.056640000000 0.000000000000 -3387.398930000000 0.000000000000 0.000000000000 4042.000000000000 642.837402000000 3387.398930000000 0.000000000000 0.000000000000 -5307.056640000000 642.837402000000 7351.768070000000 425.810211000000 4134.747070000000 5307.056640000000 0.000000000000 3387.398930000000 425.810211000000 10947.622100000001 -824.131775000000 -642.837402000000 -3387.398930000000 0.000000000000 4134.747070000000 -824.131775000000 3894.297360000000 9 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12773.459000000001 4952.860350000000 0.000000000000 5000.000000000000 0.000000000000 -12773.459000000001 0.000000000000 -5028.740230000000 0.000000000000 0.000000000000 5000.000000000000 -4952.860350000000 5028.740230000000 0.000000000000 0.000000000000 -12773.459000000001 -4952.860350000000 37890.675799999997 -5030.428710000000 12859.059600000001 12773.459000000001 0.000000000000 5028.740230000000 -5030.428710000000 38176.484400000001 12694.855500000000 4952.860350000000 -5028.740230000000 0.000000000000 12859.059600000001 12694.855500000000 10706.720700000000 9 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12612.209999999999 4413.428220000000 0.000000000000 5000.000000000000 0.000000000000 -12612.209999999999 0.000000000000 -3813.435060000000 0.000000000000 0.000000000000 5000.000000000000 -4413.428220000000 3813.435060000000 0.000000000000 0.000000000000 -12612.209999999999 -4413.428220000000 36165.035199999998 -3413.284910000000 9582.524410000000 12612.209999999999 0.000000000000 3813.435060000000 -3413.284910000000 35500.363299999997 11172.452100000000 4413.428220000000 -3813.435060000000 0.000000000000 9582.524410000000 11172.452100000000 7898.112300000000 9 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12876.370100000000 3324.440430000000 0.000000000000 5000.000000000000 0.000000000000 -12876.370100000000 0.000000000000 -2841.162350000000 0.000000000000 0.000000000000 5000.000000000000 -3324.440430000000 2841.162350000000 0.000000000000 0.000000000000 -12876.370100000000 -3324.440430000000 36482.972699999998 -2632.128910000000 7108.766110000000 12876.370100000000 0.000000000000 2841.162350000000 -2632.128910000000 36270.320299999999 8403.637699999999 3324.440430000000 -2841.162350000000 0.000000000000 7108.766110000000 8403.637699999999 6170.176760000000 9 50 60 4891.000000000000 0.000000000000 0.000000000000 0.000000000000 12532.980500000000 3279.105710000000 0.000000000000 4891.000000000000 0.000000000000 -12532.980500000000 0.000000000000 -3525.116940000000 0.000000000000 0.000000000000 4891.000000000000 -3279.105710000000 3525.116940000000 0.000000000000 0.000000000000 -12532.980500000000 -3279.105710000000 34921.515599999999 -2708.626950000000 8946.613280000000 12532.980500000000 0.000000000000 3525.116940000000 -2708.626950000000 35610.410199999998 8370.375000000000 3279.105710000000 -3525.116940000000 0.000000000000 8946.613280000000 8370.375000000000 6125.914060000000 9 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12803.181600000000 3366.422850000000 0.000000000000 5000.000000000000 0.000000000000 -12803.181600000000 0.000000000000 -3340.244380000000 0.000000000000 0.000000000000 5000.000000000000 -3366.422850000000 3340.244380000000 0.000000000000 0.000000000000 -12803.181600000000 -3366.422850000000 35502.343800000002 -2618.071040000000 8498.320309999999 12803.181600000000 0.000000000000 3340.244380000000 -2618.071040000000 36142.582000000002 8631.644530000000 3366.422850000000 -3340.244380000000 0.000000000000 8498.320309999999 8631.644530000000 5921.056640000000 9 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10925.522499999999 -460.968048000000 0.000000000000 5000.000000000000 0.000000000000 -10925.522499999999 0.000000000000 -474.903229000000 0.000000000000 0.000000000000 5000.000000000000 460.968048000000 474.903229000000 0.000000000000 0.000000000000 -10925.522499999999 460.968048000000 26572.863300000001 100.803177000000 -939.871643000000 10925.522499999999 0.000000000000 474.903229000000 100.803177000000 28564.285199999998 -935.209717000000 -460.968048000000 -474.903229000000 0.000000000000 -939.871643000000 -935.209717000000 2603.006840000000 9 56 60 4096.000000000000 0.000000000000 0.000000000000 0.000000000000 5937.436040000000 -611.021118000000 0.000000000000 4096.000000000000 0.000000000000 -5937.436040000000 0.000000000000 -2869.658450000000 0.000000000000 0.000000000000 4096.000000000000 611.021118000000 2869.658450000000 0.000000000000 0.000000000000 -5937.436040000000 611.021118000000 9558.283200000000 337.816284000000 3197.713870000000 5937.436040000000 0.000000000000 2869.658450000000 337.816284000000 13003.658200000000 -875.075684000000 -611.021118000000 -2869.658450000000 0.000000000000 3197.713870000000 -875.075684000000 3795.469970000000 9 57 60 4168.000000000000 0.000000000000 0.000000000000 0.000000000000 5777.463870000000 -626.319397000000 0.000000000000 4168.000000000000 0.000000000000 -5777.463870000000 0.000000000000 -3773.177730000000 0.000000000000 0.000000000000 4168.000000000000 626.319397000000 3773.177730000000 0.000000000000 0.000000000000 -5777.463870000000 626.319397000000 8731.527340000001 463.830658000000 4943.736820000000 5777.463870000000 0.000000000000 3773.177730000000 463.830658000000 12682.279300000000 -866.465942000000 -626.319397000000 -3773.177730000000 0.000000000000 4943.736820000000 -866.465942000000 4234.566410000000 9 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10426.275400000000 -458.451691000000 0.000000000000 5000.000000000000 0.000000000000 -10426.275400000000 0.000000000000 -2519.455570000000 0.000000000000 0.000000000000 5000.000000000000 458.451691000000 2519.455570000000 0.000000000000 0.000000000000 -10426.275400000000 458.451691000000 24495.759800000000 149.520142000000 3456.613040000000 10426.275400000000 0.000000000000 2519.455570000000 149.520142000000 27508.933600000000 -907.525879000000 -458.451691000000 -2519.455570000000 0.000000000000 3456.613040000000 -907.525879000000 3378.980960000000 10 21 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10088.806600000000 -359.111053000000 0.000000000000 5000.000000000000 0.000000000000 -10088.806600000000 0.000000000000 3769.041260000000 0.000000000000 0.000000000000 5000.000000000000 359.111053000000 -3769.041260000000 0.000000000000 0.000000000000 -10088.806600000000 359.111053000000 23098.072300000000 164.096680000000 -8737.008790000000 10088.806600000000 0.000000000000 -3769.041260000000 164.096680000000 26150.875000000000 -79.696395900000 -359.111053000000 3769.041260000000 0.000000000000 -8737.008790000000 -79.696395900000 4148.801270000000 10 24 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12634.109399999999 158.386322000000 0.000000000000 5000.000000000000 0.000000000000 -12634.109399999999 0.000000000000 4955.382810000000 0.000000000000 0.000000000000 5000.000000000000 -158.386322000000 -4955.382810000000 0.000000000000 0.000000000000 -12634.109399999999 -158.386322000000 32807.917999999998 99.716690100000 -12578.069299999999 12634.109399999999 0.000000000000 -4955.382810000000 99.716690100000 37387.980499999998 311.634857000000 158.386322000000 4955.382810000000 0.000000000000 -12578.069299999999 311.634857000000 5713.550780000000 10 28 60 3510.000000000000 0.000000000000 0.000000000000 0.000000000000 8813.430660000000 1319.693730000000 0.000000000000 3510.000000000000 0.000000000000 -8813.430660000000 0.000000000000 -3528.711910000000 0.000000000000 0.000000000000 3510.000000000000 -1319.693730000000 3528.711910000000 0.000000000000 0.000000000000 -8813.430660000000 -1319.693730000000 24378.757799999999 -1589.509640000000 9340.456050000001 8813.430660000000 0.000000000000 3528.711910000000 -1589.509640000000 27266.818400000000 3926.013430000000 1319.693730000000 -3528.711910000000 0.000000000000 9340.456050000001 3926.013430000000 5063.869630000000 10 29 60 2606.000000000000 0.000000000000 0.000000000000 0.000000000000 7345.603520000000 1207.103390000000 0.000000000000 2606.000000000000 0.000000000000 -7345.603520000000 0.000000000000 -2987.113280000000 0.000000000000 0.000000000000 2606.000000000000 -1207.103390000000 2987.113280000000 0.000000000000 0.000000000000 -7345.603520000000 -1207.103390000000 21698.294900000001 -1476.842650000000 8424.396479999999 7345.603520000000 0.000000000000 2987.113280000000 -1476.842650000000 24337.791000000001 3437.630130000000 1207.103390000000 -2987.113280000000 0.000000000000 8424.396479999999 3437.630130000000 4435.994140000000 10 34 60 4277.000000000000 0.000000000000 0.000000000000 0.000000000000 5570.097170000000 -1146.447630000000 0.000000000000 4277.000000000000 0.000000000000 -5570.097170000000 0.000000000000 -426.143127000000 0.000000000000 0.000000000000 4277.000000000000 1146.447630000000 426.143127000000 0.000000000000 0.000000000000 -5570.097170000000 1146.447630000000 7728.924800000000 72.806861900000 487.892487000000 5570.097170000000 0.000000000000 426.143127000000 72.806861900000 8295.893550000001 -1430.723020000000 -1146.447630000000 -426.143127000000 0.000000000000 487.892487000000 -1430.723020000000 1260.532590000000 10 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10679.102500000001 747.958496000000 0.000000000000 5000.000000000000 0.000000000000 -10679.102500000001 0.000000000000 3190.792240000000 0.000000000000 0.000000000000 5000.000000000000 -747.958496000000 -3190.792240000000 0.000000000000 0.000000000000 -10679.102500000001 -747.958496000000 24838.128900000000 671.415222000000 -7029.748050000000 10679.102500000001 0.000000000000 -3190.792240000000 671.415222000000 26593.906299999999 2191.075440000000 747.958496000000 3190.792240000000 0.000000000000 -7029.748050000000 2191.075440000000 3493.986080000000 10 40 60 2265.000000000000 0.000000000000 0.000000000000 0.000000000000 6321.059080000000 1619.832280000000 0.000000000000 2265.000000000000 0.000000000000 -6321.059080000000 0.000000000000 -1909.175660000000 0.000000000000 0.000000000000 2265.000000000000 -1619.832280000000 1909.175660000000 0.000000000000 0.000000000000 -6321.059080000000 -1619.832280000000 19215.410199999998 -1312.646730000000 5269.938480000000 6321.059080000000 0.000000000000 1909.175660000000 -1312.646730000000 19636.328099999999 4659.851560000000 1619.832280000000 -1909.175660000000 0.000000000000 5269.938480000000 4659.851560000000 3208.853030000000 10 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14239.424800000001 3271.273190000000 0.000000000000 5000.000000000000 0.000000000000 -14239.424800000001 0.000000000000 -4661.966800000000 0.000000000000 0.000000000000 5000.000000000000 -3271.273190000000 4661.966800000000 0.000000000000 0.000000000000 -14239.424800000001 -3271.273190000000 43599.515599999999 -3208.090090000000 13411.024400000000 14239.424800000001 0.000000000000 4661.966800000000 -3208.090090000000 45538.320299999999 9534.094730000001 3271.273190000000 -4661.966800000000 0.000000000000 13411.024400000000 9534.094730000001 7621.790530000000 10 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14123.159200000000 3392.831050000000 0.000000000000 5000.000000000000 0.000000000000 -14123.159200000000 0.000000000000 -4252.370120000000 0.000000000000 0.000000000000 5000.000000000000 -3392.831050000000 4252.370120000000 0.000000000000 0.000000000000 -14123.159200000000 -3392.831050000000 42836.878900000003 -2870.120120000000 12059.038100000000 14123.159200000000 0.000000000000 4252.370120000000 -2870.120120000000 44060.414100000002 9745.465819999999 3392.831050000000 -4252.370120000000 0.000000000000 12059.038100000000 9745.465819999999 6839.367680000000 10 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14159.380900000000 3874.186770000000 0.000000000000 5000.000000000000 0.000000000000 -14159.380900000000 0.000000000000 -4288.247560000000 0.000000000000 0.000000000000 5000.000000000000 -3874.186770000000 4288.247560000000 0.000000000000 0.000000000000 -14159.380900000000 -3874.186770000000 43582.582000000002 -3309.925290000000 12169.699199999999 14159.380900000000 0.000000000000 4288.247560000000 -3309.925290000000 44420.363299999997 11123.786099999999 3874.186770000000 -4288.247560000000 0.000000000000 12169.699199999999 11123.786099999999 7550.065430000000 10 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14164.862300000001 3919.844970000000 0.000000000000 5000.000000000000 0.000000000000 -14164.862300000001 0.000000000000 -4029.159670000000 0.000000000000 0.000000000000 5000.000000000000 -3919.844970000000 4029.159670000000 0.000000000000 0.000000000000 -14164.862300000001 -3919.844970000000 43679.792999999998 -3134.766360000000 11454.652300000000 14164.862300000001 0.000000000000 4029.159670000000 -3134.766360000000 44202.292999999998 11249.950199999999 3919.844970000000 -4029.159670000000 0.000000000000 11454.652300000000 11249.950199999999 7378.811040000000 10 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14109.420899999999 4124.621580000000 0.000000000000 5000.000000000000 0.000000000000 -14109.420899999999 0.000000000000 -3384.759770000000 0.000000000000 0.000000000000 5000.000000000000 -4124.621580000000 3384.759770000000 0.000000000000 0.000000000000 -14109.420899999999 -4124.621580000000 43702.226600000002 -2879.090330000000 9806.382809999999 14109.420899999999 0.000000000000 3384.759770000000 -2879.090330000000 43632.667999999998 11800.706099999999 4124.621580000000 -3384.759770000000 0.000000000000 9806.382809999999 11800.706099999999 7352.716800000000 10 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13367.410200000000 3653.874760000000 0.000000000000 5000.000000000000 0.000000000000 -13367.410200000000 0.000000000000 -1133.067500000000 0.000000000000 0.000000000000 5000.000000000000 -3653.874760000000 1133.067500000000 0.000000000000 0.000000000000 -13367.410200000000 -3653.874760000000 38860.050799999997 -976.720947000000 3357.834470000000 13367.410200000000 0.000000000000 1133.067500000000 -976.720947000000 37597.015599999999 9923.600590000000 3653.874760000000 -1133.067500000000 0.000000000000 3357.834470000000 9923.600590000000 4633.411130000000 10 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12563.464800000000 3077.891850000000 0.000000000000 5000.000000000000 0.000000000000 -12563.464800000000 0.000000000000 1534.733520000000 0.000000000000 0.000000000000 5000.000000000000 -3077.891850000000 -1534.733520000000 0.000000000000 0.000000000000 -12563.464800000000 -3077.891850000000 33936.812500000000 800.142456000000 -3614.430660000000 12563.464800000000 0.000000000000 -1534.733520000000 800.142456000000 33345.015599999999 7867.183110000000 3077.891850000000 1534.733520000000 0.000000000000 -3614.430660000000 7867.183110000000 3836.740970000000 10 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12300.722700000000 2728.835940000000 0.000000000000 5000.000000000000 0.000000000000 -12300.722700000000 0.000000000000 2450.135990000000 0.000000000000 0.000000000000 5000.000000000000 -2728.835940000000 -2450.135990000000 0.000000000000 0.000000000000 -12300.722700000000 -2728.835940000000 32221.918000000001 1175.662720000000 -5809.118650000000 12300.722700000000 0.000000000000 -2450.135990000000 1175.662720000000 32627.880900000000 6834.423830000000 2728.835940000000 2450.135990000000 0.000000000000 -5809.118650000000 6834.423830000000 4021.836430000000 10 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12198.102500000001 2660.854980000000 0.000000000000 5000.000000000000 0.000000000000 -12198.102500000001 0.000000000000 2677.365230000000 0.000000000000 0.000000000000 5000.000000000000 -2660.854980000000 -2677.365230000000 0.000000000000 0.000000000000 -12198.102500000001 -2660.854980000000 31714.998000000000 1268.657100000000 -6316.751950000000 12198.102500000001 0.000000000000 -2677.365230000000 1268.657100000000 32352.560500000000 6588.249510000000 2660.854980000000 2677.365230000000 0.000000000000 -6316.751950000000 6588.249510000000 4235.303710000000 10 50 60 4124.000000000000 0.000000000000 0.000000000000 0.000000000000 10210.219700000000 2103.453130000000 0.000000000000 4124.000000000000 0.000000000000 -10210.219700000000 0.000000000000 1892.339360000000 0.000000000000 0.000000000000 4124.000000000000 -2103.453130000000 -1892.339360000000 0.000000000000 0.000000000000 -10210.219700000000 -2103.453130000000 26725.197300000000 873.731079000000 -4526.098140000000 10210.219700000000 0.000000000000 -1892.339360000000 873.731079000000 27029.218799999999 5306.302730000000 2103.453130000000 1892.339360000000 0.000000000000 -4526.098140000000 5306.302730000000 2943.307370000000 10 51 60 1968.000000000000 0.000000000000 0.000000000000 0.000000000000 5096.282230000000 1185.995480000000 0.000000000000 1968.000000000000 0.000000000000 -5096.282230000000 0.000000000000 245.984756000000 0.000000000000 0.000000000000 1968.000000000000 -1185.995480000000 -245.984756000000 0.000000000000 0.000000000000 -5096.282230000000 -1185.995480000000 14031.208000000001 104.365959000000 -569.204834000000 5096.282230000000 0.000000000000 -245.984756000000 104.365959000000 13481.100600000000 3116.858890000000 1185.995480000000 245.984756000000 0.000000000000 -569.204834000000 3116.858890000000 999.749268000000 10 52 60 4596.000000000000 0.000000000000 0.000000000000 0.000000000000 11316.690399999999 2316.257810000000 0.000000000000 4596.000000000000 0.000000000000 -11316.690399999999 0.000000000000 2275.407960000000 0.000000000000 0.000000000000 4596.000000000000 -2316.257810000000 -2275.407960000000 0.000000000000 0.000000000000 -11316.690399999999 -2316.257810000000 29408.068400000000 1030.598390000000 -5415.346680000000 11316.690399999999 0.000000000000 -2275.407960000000 1030.598390000000 30004.345700000002 5818.095210000000 2316.257810000000 2275.407960000000 0.000000000000 -5415.346680000000 5818.095210000000 3406.208980000000 10 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12037.847700000000 2239.129640000000 0.000000000000 5000.000000000000 0.000000000000 -12037.847700000000 0.000000000000 2666.921880000000 0.000000000000 0.000000000000 5000.000000000000 -2239.129640000000 -2666.921880000000 0.000000000000 0.000000000000 -12037.847700000000 -2239.129640000000 30669.210899999998 1134.668460000000 -6268.243650000000 12037.847700000000 0.000000000000 -2666.921880000000 1134.668460000000 31408.259800000000 5594.937500000000 2239.129640000000 2666.921880000000 0.000000000000 -6268.243650000000 5594.937500000000 3658.723390000000 10 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9671.415040000000 140.756454000000 0.000000000000 5000.000000000000 0.000000000000 -9671.415040000000 0.000000000000 2492.769780000000 0.000000000000 0.000000000000 5000.000000000000 -140.756454000000 -2492.769780000000 0.000000000000 0.000000000000 -9671.415040000000 -140.756454000000 20829.408200000002 470.459473000000 -5289.375490000000 9671.415040000000 0.000000000000 -2492.769780000000 470.459473000000 21960.083999999999 1027.700320000000 140.756454000000 2492.769780000000 0.000000000000 -5289.375490000000 1027.700320000000 2554.216550000000 10 55 60 3291.000000000000 0.000000000000 0.000000000000 0.000000000000 4591.087400000000 -957.235291000000 0.000000000000 3291.000000000000 0.000000000000 -4591.087400000000 0.000000000000 549.103882000000 0.000000000000 0.000000000000 3291.000000000000 957.235291000000 -549.103882000000 0.000000000000 0.000000000000 -4591.087400000000 957.235291000000 7168.179200000000 -155.636505000000 -1095.978760000000 4591.087400000000 0.000000000000 -549.103882000000 -155.636505000000 7440.161130000000 -1292.609010000000 -957.235291000000 549.103882000000 0.000000000000 -1095.978760000000 -1292.609010000000 885.186646000000 10 56 60 3666.000000000000 0.000000000000 0.000000000000 0.000000000000 4734.445310000000 -1044.029910000000 0.000000000000 3666.000000000000 0.000000000000 -4734.445310000000 0.000000000000 -73.697181700000 0.000000000000 0.000000000000 3666.000000000000 1044.029910000000 73.697181700000 0.000000000000 0.000000000000 -4734.445310000000 1044.029910000000 6544.604000000000 17.520729100000 14.285542500000 4734.445310000000 0.000000000000 73.697181700000 17.520729100000 6649.031740000000 -1306.139650000000 -1044.029910000000 -73.697181700000 0.000000000000 14.285542500000 -1306.139650000000 740.464539000000 10 57 60 4171.000000000000 0.000000000000 0.000000000000 0.000000000000 5489.669430000000 -1176.758540000000 0.000000000000 4171.000000000000 0.000000000000 -5489.669430000000 0.000000000000 -310.620819000000 0.000000000000 0.000000000000 4171.000000000000 1176.758540000000 310.620819000000 0.000000000000 0.000000000000 -5489.669430000000 1176.758540000000 7858.812990000000 71.428100600000 280.861115000000 5489.669430000000 0.000000000000 310.620819000000 71.428100600000 7930.423340000000 -1502.382690000000 -1176.758540000000 -310.620819000000 0.000000000000 280.861115000000 -1502.382690000000 784.437927000000 10 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7674.118650000000 -1110.089110000000 0.000000000000 5000.000000000000 0.000000000000 -7674.118650000000 0.000000000000 264.986389000000 0.000000000000 0.000000000000 5000.000000000000 1110.089110000000 -264.986389000000 0.000000000000 0.000000000000 -7674.118650000000 1110.089110000000 13159.949199999999 -0.342617244000 -808.220459000000 7674.118650000000 0.000000000000 -264.986389000000 -0.342617244000 13399.151400000001 -1460.321780000000 -1110.089110000000 264.986389000000 0.000000000000 -808.220459000000 -1460.321780000000 960.007080000000 10 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9904.931640000001 -395.783875000000 0.000000000000 5000.000000000000 0.000000000000 -9904.931640000001 0.000000000000 145.522675000000 0.000000000000 0.000000000000 5000.000000000000 395.783875000000 -145.522675000000 0.000000000000 0.000000000000 -9904.931640000001 395.783875000000 21419.693400000000 -140.428467000000 -84.641914400000 9904.931640000001 0.000000000000 -145.522675000000 -140.428467000000 21729.396499999999 -366.323212000000 -395.783875000000 145.522675000000 0.000000000000 -84.641914400000 -366.323212000000 850.240967000000 11 16 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9528.597659999999 364.150421000000 0.000000000000 5000.000000000000 0.000000000000 -9528.597659999999 0.000000000000 1396.420530000000 0.000000000000 0.000000000000 5000.000000000000 -364.150421000000 -1396.420530000000 0.000000000000 0.000000000000 -9528.597659999999 -364.150421000000 20022.156299999999 270.486908000000 -2808.346920000000 9528.597659999999 0.000000000000 -1396.420530000000 270.486908000000 20498.703099999999 1210.745730000000 364.150421000000 1396.420530000000 0.000000000000 -2808.346920000000 1210.745730000000 1430.702760000000 11 17 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9444.116210000000 573.179260000000 0.000000000000 5000.000000000000 0.000000000000 -9444.116210000000 0.000000000000 2044.980830000000 0.000000000000 0.000000000000 5000.000000000000 -573.179260000000 -2044.980830000000 0.000000000000 0.000000000000 -9444.116210000000 -573.179260000000 19986.410199999998 440.325287000000 -4142.444820000000 9444.116210000000 0.000000000000 -2044.980830000000 440.325287000000 20563.242200000001 1728.473390000000 573.179260000000 2044.980830000000 0.000000000000 -4142.444820000000 1728.473390000000 1980.505000000000 11 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9928.612300000001 1277.125240000000 0.000000000000 5000.000000000000 0.000000000000 -9928.612300000001 0.000000000000 1209.098140000000 0.000000000000 0.000000000000 5000.000000000000 -1277.125240000000 -1209.098140000000 0.000000000000 0.000000000000 -9928.612300000001 -1277.125240000000 22043.556600000000 608.175537000000 -2554.256590000000 9928.612300000001 0.000000000000 -1209.098140000000 608.175537000000 21876.603500000001 3264.391600000000 1277.125240000000 1209.098140000000 0.000000000000 -2554.256590000000 3264.391600000000 2038.217040000000 11 21 60 3845.000000000000 0.000000000000 0.000000000000 0.000000000000 8332.181640000001 746.028076000000 0.000000000000 3845.000000000000 0.000000000000 -8332.181640000001 0.000000000000 3451.405270000000 0.000000000000 0.000000000000 3845.000000000000 -746.028076000000 -3451.405270000000 0.000000000000 0.000000000000 -8332.181640000001 -746.028076000000 19813.539100000002 849.487183000000 -7980.560060000000 8332.181640000001 0.000000000000 -3451.405270000000 849.487183000000 22602.333999999999 1978.010010000000 746.028076000000 3451.405270000000 0.000000000000 -7980.560060000000 1978.010010000000 3948.793700000000 11 24 60 4059.000000000000 0.000000000000 0.000000000000 0.000000000000 9979.610350000001 1136.219360000000 0.000000000000 4059.000000000000 0.000000000000 -9979.610350000001 0.000000000000 3878.672850000000 0.000000000000 0.000000000000 4059.000000000000 -1136.219360000000 -3878.672850000000 0.000000000000 0.000000000000 -9979.610350000001 -1136.219360000000 25413.906299999999 1015.247860000000 -9583.779300000000 9979.610350000001 0.000000000000 -3878.672850000000 1015.247860000000 28517.605500000001 2686.739750000000 1136.219360000000 3878.672850000000 0.000000000000 -9583.779300000000 2686.739750000000 4573.854000000000 11 29 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11461.719700000000 -298.090210000000 0.000000000000 5000.000000000000 0.000000000000 -11461.719700000000 0.000000000000 -6229.574220000000 0.000000000000 0.000000000000 5000.000000000000 298.090210000000 6229.574220000000 0.000000000000 0.000000000000 -11461.719700000000 298.090210000000 27413.195299999999 314.975067000000 14214.091800000000 11461.719700000000 0.000000000000 6229.574220000000 314.975067000000 34597.429700000001 -529.286499000000 -298.090210000000 -6229.574220000000 0.000000000000 14214.091800000000 -529.286499000000 8551.909180000001 11 35 60 3558.000000000000 0.000000000000 0.000000000000 0.000000000000 7922.868160000000 1457.935180000000 0.000000000000 3558.000000000000 0.000000000000 -7922.868160000000 0.000000000000 2000.622070000000 0.000000000000 0.000000000000 3558.000000000000 -1457.935180000000 -2000.622070000000 0.000000000000 0.000000000000 -7922.868160000000 -1457.935180000000 18680.289100000002 934.359558000000 -4525.563960000000 7922.868160000000 0.000000000000 -2000.622070000000 934.359558000000 19199.002000000000 3322.449220000000 1457.935180000000 2000.622070000000 0.000000000000 -4525.563960000000 3322.449220000000 2400.445070000000 11 40 60 3266.000000000000 0.000000000000 0.000000000000 0.000000000000 7601.010250000000 1008.528810000000 0.000000000000 3266.000000000000 0.000000000000 -7601.010250000000 0.000000000000 -2985.978270000000 0.000000000000 0.000000000000 3266.000000000000 -1008.528810000000 2985.978270000000 0.000000000000 0.000000000000 -7601.010250000000 -1008.528810000000 19556.597699999998 -895.426392000000 6969.521000000000 7601.010250000000 0.000000000000 2985.978270000000 -895.426392000000 21428.085899999998 2830.828860000000 1008.528810000000 -2985.978270000000 0.000000000000 6969.521000000000 2830.828860000000 4093.006100000000 11 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12290.225600000000 1958.124760000000 0.000000000000 5000.000000000000 0.000000000000 -12290.225600000000 0.000000000000 -5013.540530000000 0.000000000000 0.000000000000 5000.000000000000 -1958.124760000000 5013.540530000000 0.000000000000 0.000000000000 -12290.225600000000 -1958.124760000000 32191.025399999999 -1982.724980000000 12238.638700000000 12290.225600000000 0.000000000000 5013.540530000000 -1982.724980000000 36146.382799999999 5172.018070000000 1958.124760000000 -5013.540530000000 0.000000000000 12238.638700000000 5172.018070000000 6928.150390000000 11 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12359.333000000001 2119.130370000000 0.000000000000 5000.000000000000 0.000000000000 -12359.333000000001 0.000000000000 -4791.295410000000 0.000000000000 0.000000000000 5000.000000000000 -2119.130370000000 4791.295410000000 0.000000000000 0.000000000000 -12359.333000000001 -2119.130370000000 32439.279299999998 -1867.973020000000 11656.263700000000 12359.333000000001 0.000000000000 4791.295410000000 -1867.973020000000 35910.835899999998 5531.360350000000 2119.130370000000 -4791.295410000000 0.000000000000 11656.263700000000 5531.360350000000 6562.924320000000 11 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12509.889600000000 2869.279540000000 0.000000000000 5000.000000000000 0.000000000000 -12509.889600000000 0.000000000000 -4741.387210000000 0.000000000000 0.000000000000 5000.000000000000 -2869.279540000000 4741.387210000000 0.000000000000 0.000000000000 -12509.889600000000 -2869.279540000000 33709.832000000002 -2471.263180000000 11663.593800000001 12509.889600000000 0.000000000000 4741.387210000000 -2471.263180000000 36577.187500000000 7458.987300000000 2869.279540000000 -4741.387210000000 0.000000000000 11663.593800000001 7458.987300000000 7157.025390000000 11 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12812.661099999999 3188.676030000000 0.000000000000 5000.000000000000 0.000000000000 -12812.661099999999 0.000000000000 -4134.845700000000 0.000000000000 0.000000000000 5000.000000000000 -3188.676030000000 4134.845700000000 0.000000000000 0.000000000000 -12812.661099999999 -3188.676030000000 35460.519500000002 -2372.377930000000 10476.125000000000 12812.661099999999 0.000000000000 4134.845700000000 -2372.377930000000 37030.957000000002 8343.578130000000 3188.676030000000 -4134.845700000000 0.000000000000 10476.125000000000 8343.578130000000 6536.799320000000 11 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12697.372100000001 3410.501710000000 0.000000000000 5000.000000000000 0.000000000000 -12697.372100000001 0.000000000000 -3337.760010000000 0.000000000000 0.000000000000 5000.000000000000 -3410.501710000000 3337.760010000000 0.000000000000 0.000000000000 -12697.372100000001 -3410.501710000000 35011.363299999997 -2135.482420000000 8522.326170000000 12697.372100000001 0.000000000000 3337.760010000000 -2135.482420000000 35474.179700000001 8791.374019999999 3410.501710000000 -3337.760010000000 0.000000000000 8522.326170000000 8791.374019999999 5757.909180000000 11 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12200.260700000001 3390.064940000000 0.000000000000 5000.000000000000 0.000000000000 -12200.260700000001 0.000000000000 -1227.052370000000 0.000000000000 0.000000000000 5000.000000000000 -3390.064940000000 1227.052370000000 0.000000000000 0.000000000000 -12200.260700000001 -3390.064940000000 32479.783200000002 -734.643005000000 3230.430660000000 12200.260700000001 0.000000000000 1227.052370000000 -734.643005000000 31527.687500000000 8380.344730000001 3390.064940000000 -1227.052370000000 0.000000000000 3230.430660000000 8380.344730000001 4187.634280000000 11 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11853.342800000000 3498.974610000000 0.000000000000 5000.000000000000 0.000000000000 -11853.342800000000 0.000000000000 811.055603000000 0.000000000000 0.000000000000 5000.000000000000 -3498.974610000000 -811.055603000000 0.000000000000 0.000000000000 -11853.342800000000 -3498.974610000000 30868.402300000002 554.073547000000 -1663.424320000000 11853.342800000000 0.000000000000 -811.055603000000 554.073547000000 29742.523399999998 8379.684569999999 3498.974610000000 811.055603000000 0.000000000000 -1663.424320000000 8379.684569999999 4136.940920000000 11 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11593.025400000000 3289.634770000000 0.000000000000 5000.000000000000 0.000000000000 -11593.025400000000 0.000000000000 1724.877320000000 0.000000000000 0.000000000000 5000.000000000000 -3289.634770000000 -1724.877320000000 0.000000000000 0.000000000000 -11593.025400000000 -3289.634770000000 29393.087899999999 1137.412350000000 -3830.887210000000 11593.025400000000 0.000000000000 -1724.877320000000 1137.412350000000 28467.953099999999 7723.199220000000 3289.634770000000 1724.877320000000 0.000000000000 -3830.887210000000 7723.199220000000 3824.299320000000 11 49 60 4843.000000000000 0.000000000000 0.000000000000 0.000000000000 11180.442400000000 3146.191650000000 0.000000000000 4843.000000000000 0.000000000000 -11180.442400000000 0.000000000000 1766.846560000000 0.000000000000 0.000000000000 4843.000000000000 -3146.191650000000 -1766.846560000000 0.000000000000 0.000000000000 -11180.442400000000 -3146.191650000000 28173.724600000001 1135.230710000000 -3974.503910000000 11180.442400000000 0.000000000000 -1766.846560000000 1135.230710000000 27243.798800000000 7356.562010000000 3146.191650000000 1766.846560000000 0.000000000000 -3974.503910000000 7356.562010000000 3586.495610000000 11 50 60 4475.000000000000 0.000000000000 0.000000000000 0.000000000000 10452.304700000001 2849.321290000000 0.000000000000 4475.000000000000 0.000000000000 -10452.304700000001 0.000000000000 1164.241700000000 0.000000000000 0.000000000000 4475.000000000000 -2849.321290000000 -1164.241700000000 0.000000000000 0.000000000000 -10452.304700000001 -2849.321290000000 26573.197300000000 758.444336000000 -2554.636960000000 10452.304700000001 0.000000000000 -1164.241700000000 758.444336000000 25519.892599999999 6755.543460000000 2849.321290000000 1164.241700000000 0.000000000000 -2554.636960000000 6755.543460000000 2993.989260000000 11 51 60 3083.000000000000 0.000000000000 0.000000000000 0.000000000000 7350.546390000000 1939.534910000000 0.000000000000 3083.000000000000 0.000000000000 -7350.546390000000 0.000000000000 196.820267000000 0.000000000000 0.000000000000 3083.000000000000 -1939.534910000000 -196.820267000000 0.000000000000 0.000000000000 -7350.546390000000 -1939.534910000000 18971.257799999999 125.087250000000 -368.127289000000 7350.546390000000 0.000000000000 -196.820267000000 125.087250000000 17927.472699999998 4689.316890000000 1939.534910000000 196.820267000000 0.000000000000 -368.127289000000 4689.316890000000 1670.800780000000 11 52 60 4698.000000000000 0.000000000000 0.000000000000 0.000000000000 10897.604499999999 2950.593510000000 0.000000000000 4698.000000000000 0.000000000000 -10897.604499999999 0.000000000000 1392.775270000000 0.000000000000 0.000000000000 4698.000000000000 -2950.593510000000 -1392.775270000000 0.000000000000 0.000000000000 -10897.604499999999 -2950.593510000000 27489.775399999999 897.296753000000 -3087.629880000000 10897.604499999999 0.000000000000 -1392.775270000000 897.296753000000 26534.937500000000 6943.325200000000 2950.593510000000 1392.775270000000 0.000000000000 -3087.629880000000 6943.325200000000 3224.211670000000 11 53 60 4741.000000000000 0.000000000000 0.000000000000 0.000000000000 10763.305700000001 2653.582280000000 0.000000000000 4741.000000000000 0.000000000000 -10763.305700000001 0.000000000000 1961.786740000000 0.000000000000 0.000000000000 4741.000000000000 -2653.582280000000 -1961.786740000000 0.000000000000 0.000000000000 -10763.305700000001 -2653.582280000000 26360.066400000000 1145.046880000000 -4416.230470000000 10763.305700000001 0.000000000000 -1961.786740000000 1145.046880000000 25902.953099999999 6139.775390000000 2653.582280000000 1961.786740000000 0.000000000000 -4416.230470000000 6139.775390000000 3230.344730000000 11 54 60 4321.000000000000 0.000000000000 0.000000000000 0.000000000000 8004.727050000000 788.258606000000 0.000000000000 4321.000000000000 0.000000000000 -8004.727050000000 0.000000000000 2053.582280000000 0.000000000000 0.000000000000 4321.000000000000 -788.258606000000 -2053.582280000000 0.000000000000 0.000000000000 -8004.727050000000 -788.258606000000 16732.386699999999 676.228882000000 -4121.486820000000 8004.727050000000 0.000000000000 -2053.582280000000 676.228882000000 17208.048800000000 2129.201420000000 788.258606000000 2053.582280000000 0.000000000000 -4121.486820000000 2129.201420000000 2107.630370000000 11 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7083.165040000000 -778.095093000000 0.000000000000 5000.000000000000 0.000000000000 -7083.165040000000 0.000000000000 905.502869000000 0.000000000000 0.000000000000 5000.000000000000 778.095093000000 -905.502869000000 0.000000000000 0.000000000000 -7083.165040000000 778.095093000000 11288.778300000000 -39.075161000000 -1594.692260000000 7083.165040000000 0.000000000000 -905.502869000000 -39.075161000000 11543.155300000000 -816.055542000000 -778.095093000000 905.502869000000 0.000000000000 -1594.692260000000 -816.055542000000 774.339722000000 11 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9906.794920000000 67.573715200000 0.000000000000 5000.000000000000 0.000000000000 -9906.794920000000 0.000000000000 197.138885000000 0.000000000000 0.000000000000 5000.000000000000 -67.573715200000 -197.138885000000 0.000000000000 0.000000000000 -9906.794920000000 -67.573715200000 21063.552700000000 -45.920040100000 -144.012131000000 9906.794920000000 0.000000000000 -197.138885000000 -45.920040100000 21339.750000000000 426.132324000000 67.573715200000 197.138885000000 0.000000000000 -144.012131000000 426.132324000000 671.458679000000 12 16 60 4121.000000000000 0.000000000000 0.000000000000 0.000000000000 7438.240230000000 452.512299000000 0.000000000000 4121.000000000000 0.000000000000 -7438.240230000000 0.000000000000 2305.541990000000 0.000000000000 0.000000000000 4121.000000000000 -452.512299000000 -2305.541990000000 0.000000000000 0.000000000000 -7438.240230000000 -452.512299000000 14190.953100000001 322.768524000000 -4237.351070000000 7438.240230000000 0.000000000000 -2305.541990000000 322.768524000000 15371.468800000001 942.964478000000 452.512299000000 2305.541990000000 0.000000000000 -4237.351070000000 942.964478000000 1726.909180000000 12 18 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8750.992190000001 691.476196000000 0.000000000000 5000.000000000000 0.000000000000 -8750.992190000001 0.000000000000 2564.832520000000 0.000000000000 0.000000000000 5000.000000000000 -691.476196000000 -2564.832520000000 0.000000000000 0.000000000000 -8750.992190000001 -691.476196000000 16773.576200000000 572.887390000000 -4737.212890000000 8750.992190000001 0.000000000000 -2564.832520000000 572.887390000000 17878.599600000001 1578.157100000000 691.476196000000 2564.832520000000 0.000000000000 -4737.212890000000 1578.157100000000 2288.617920000000 12 20 60 3459.000000000000 0.000000000000 0.000000000000 0.000000000000 6146.352540000000 931.911377000000 0.000000000000 3459.000000000000 0.000000000000 -6146.352540000000 0.000000000000 2018.366940000000 0.000000000000 0.000000000000 3459.000000000000 -931.911377000000 -2018.366940000000 0.000000000000 0.000000000000 -6146.352540000000 -931.911377000000 11994.510700000001 694.015503000000 -3680.842040000000 6146.352540000000 0.000000000000 -2018.366940000000 694.015503000000 12716.351600000000 1925.913570000000 931.911377000000 2018.366940000000 0.000000000000 -3680.842040000000 1925.913570000000 1924.932370000000 12 25 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10287.692400000000 1785.730350000000 0.000000000000 5000.000000000000 0.000000000000 -10287.692400000000 0.000000000000 2016.325810000000 0.000000000000 0.000000000000 5000.000000000000 -1785.730350000000 -2016.325810000000 0.000000000000 0.000000000000 -10287.692400000000 -1785.730350000000 22675.996100000000 736.361206000000 -3992.703130000000 10287.692400000000 0.000000000000 -2016.325810000000 736.361206000000 22576.789100000002 3810.698970000000 1785.730350000000 2016.325810000000 0.000000000000 -3992.703130000000 3810.698970000000 2438.557620000000 12 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8736.699220000000 654.547180000000 0.000000000000 5000.000000000000 0.000000000000 -8736.699220000000 0.000000000000 -4932.694820000000 0.000000000000 0.000000000000 5000.000000000000 -654.547180000000 4932.694820000000 0.000000000000 0.000000000000 -8736.699220000000 -654.547180000000 16527.609400000001 -757.669800000000 8558.450199999999 8736.699220000000 0.000000000000 4932.694820000000 -757.669800000000 20857.515599999999 1575.739870000000 654.547180000000 -4932.694820000000 0.000000000000 8558.450199999999 1575.739870000000 5847.465820000000 12 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8055.978030000000 -981.947021000000 0.000000000000 5000.000000000000 0.000000000000 -8055.978030000000 0.000000000000 -4370.793460000000 0.000000000000 0.000000000000 5000.000000000000 981.947021000000 4370.793460000000 0.000000000000 0.000000000000 -8055.978030000000 981.947021000000 13837.548800000000 816.620483000000 7069.588380000000 8055.978030000000 0.000000000000 4370.793460000000 816.620483000000 17392.263700000000 -1509.724370000000 -981.947021000000 -4370.793460000000 0.000000000000 7069.588380000000 -1509.724370000000 4625.679200000000 12 32 60 4321.000000000000 0.000000000000 0.000000000000 0.000000000000 6094.764160000000 -1098.127320000000 0.000000000000 4321.000000000000 0.000000000000 -6094.764160000000 0.000000000000 -3267.641850000000 0.000000000000 0.000000000000 4321.000000000000 1098.127320000000 3267.641850000000 0.000000000000 0.000000000000 -6094.764160000000 1098.127320000000 9339.826170000000 858.400574000000 4927.583980000000 6094.764160000000 0.000000000000 3267.641850000000 858.400574000000 12110.633800000000 -1569.588500000000 -1098.127320000000 -3267.641850000000 0.000000000000 4927.583980000000 -1569.588500000000 3590.926510000000 12 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8876.402340000001 755.305054000000 0.000000000000 5000.000000000000 0.000000000000 -8876.402340000001 0.000000000000 2685.715820000000 0.000000000000 0.000000000000 5000.000000000000 -755.305054000000 -2685.715820000000 0.000000000000 0.000000000000 -8876.402340000001 -755.305054000000 16943.668000000001 519.158264000000 -4862.483890000000 8876.402340000001 0.000000000000 -2685.715820000000 519.158264000000 18257.339800000002 1612.434940000000 755.305054000000 2685.715820000000 0.000000000000 -4862.483890000000 1612.434940000000 2265.547360000000 12 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8929.208979999999 141.320602000000 0.000000000000 5000.000000000000 0.000000000000 -8929.208979999999 0.000000000000 1448.675170000000 0.000000000000 0.000000000000 5000.000000000000 -141.320602000000 -1448.675170000000 0.000000000000 0.000000000000 -8929.208979999999 -141.320602000000 17226.027300000002 192.725815000000 -2637.936040000000 8929.208979999999 0.000000000000 -1448.675170000000 192.725815000000 17989.115200000000 484.872101000000 141.320602000000 1448.675170000000 0.000000000000 -2637.936040000000 484.872101000000 1276.948850000000 12 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8704.715819999999 464.921753000000 0.000000000000 5000.000000000000 0.000000000000 -8704.715819999999 0.000000000000 1696.569340000000 0.000000000000 0.000000000000 5000.000000000000 -464.921753000000 -1696.569340000000 0.000000000000 0.000000000000 -8704.715819999999 -464.921753000000 16779.074199999999 378.193207000000 -3062.621340000000 8704.715819999999 0.000000000000 -1696.569340000000 378.193207000000 17411.628900000000 1249.060300000000 464.921753000000 1696.569340000000 0.000000000000 -3062.621340000000 1249.060300000000 1602.982060000000 12 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10789.869100000000 3070.203610000000 0.000000000000 5000.000000000000 0.000000000000 -10789.869100000000 0.000000000000 928.884949000000 0.000000000000 0.000000000000 5000.000000000000 -3070.203610000000 -928.884949000000 0.000000000000 0.000000000000 -10789.869100000000 -3070.203610000000 25613.085899999998 581.412964000000 -1753.173340000000 10789.869100000000 0.000000000000 -928.884949000000 581.412964000000 24520.531299999999 6767.275390000000 3070.203610000000 928.884949000000 0.000000000000 -1753.173340000000 6767.275390000000 3137.331540000000 12 47 60 3430.000000000000 0.000000000000 0.000000000000 0.000000000000 7129.840330000000 2179.546630000000 0.000000000000 3430.000000000000 0.000000000000 -7129.840330000000 0.000000000000 1551.608890000000 0.000000000000 0.000000000000 3430.000000000000 -2179.546630000000 -1551.608890000000 0.000000000000 0.000000000000 -7129.840330000000 -2179.546630000000 16517.958999999999 891.848511000000 -3019.200440000000 7129.840330000000 0.000000000000 -1551.608890000000 891.848511000000 16150.754900000000 4648.368650000000 2179.546630000000 1551.608890000000 0.000000000000 -3019.200440000000 4648.368650000000 2673.999760000000 12 48 60 2889.000000000000 0.000000000000 0.000000000000 0.000000000000 5846.014160000000 1759.461180000000 0.000000000000 2889.000000000000 0.000000000000 -5846.014160000000 0.000000000000 1805.324220000000 0.000000000000 0.000000000000 2889.000000000000 -1759.461180000000 -1805.324220000000 0.000000000000 0.000000000000 -5846.014160000000 -1759.461180000000 13161.221700000000 1065.935180000000 -3560.624020000000 5846.014160000000 0.000000000000 -1805.324220000000 1065.935180000000 13230.334999999999 3656.397710000000 1759.461180000000 1805.324220000000 0.000000000000 -3560.624020000000 3656.397710000000 2470.677490000000 12 50 60 2580.000000000000 0.000000000000 0.000000000000 0.000000000000 5302.568360000000 1655.096310000000 0.000000000000 2580.000000000000 0.000000000000 -5302.568360000000 0.000000000000 1583.478640000000 0.000000000000 0.000000000000 2580.000000000000 -1655.096310000000 -1583.478640000000 0.000000000000 0.000000000000 -5302.568360000000 -1655.096310000000 12171.391600000001 983.176941000000 -3165.683350000000 5302.568360000000 0.000000000000 -1583.478640000000 983.176941000000 12107.030300000000 3475.947510000000 1655.096310000000 1583.478640000000 0.000000000000 -3165.683350000000 3475.947510000000 2257.576660000000 12 51 60 2653.000000000000 0.000000000000 0.000000000000 0.000000000000 5552.105470000000 1762.498410000000 0.000000000000 2653.000000000000 0.000000000000 -5552.105470000000 0.000000000000 1505.717650000000 0.000000000000 0.000000000000 2653.000000000000 -1762.498410000000 -1505.717650000000 0.000000000000 0.000000000000 -5552.105470000000 -1762.498410000000 12988.237300000001 975.307739000000 -3043.090090000000 5552.105470000000 0.000000000000 -1505.717650000000 975.307739000000 12758.514600000000 3748.996580000000 1762.498410000000 1505.717650000000 0.000000000000 -3043.090090000000 3748.996580000000 2286.644290000000 12 52 60 2427.000000000000 0.000000000000 0.000000000000 0.000000000000 4962.620120000000 1552.715580000000 0.000000000000 2427.000000000000 0.000000000000 -4962.620120000000 0.000000000000 1498.674560000000 0.000000000000 0.000000000000 2427.000000000000 -1552.715580000000 -1498.674560000000 0.000000000000 0.000000000000 -4962.620120000000 -1552.715580000000 11322.459000000001 943.242004000000 -2996.957280000000 4962.620120000000 0.000000000000 -1498.674560000000 943.242004000000 11271.398400000000 3235.824950000000 1552.715580000000 1498.674560000000 0.000000000000 -2996.957280000000 3235.824950000000 2103.145260000000 12 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9325.121090000001 287.816925000000 0.000000000000 5000.000000000000 0.000000000000 -9325.121090000001 0.000000000000 2202.881840000000 0.000000000000 0.000000000000 5000.000000000000 -287.816925000000 -2202.881840000000 0.000000000000 0.000000000000 -9325.121090000001 -287.816925000000 18260.148399999998 143.334976000000 -4045.845950000000 9325.121090000001 0.000000000000 -2202.881840000000 143.334976000000 19347.154299999998 646.188965000000 287.816925000000 2202.881840000000 0.000000000000 -4045.845950000000 646.188965000000 1460.561280000000 13 18 60 3222.000000000000 0.000000000000 0.000000000000 0.000000000000 5746.304200000000 100.834816000000 0.000000000000 3222.000000000000 0.000000000000 -5746.304200000000 0.000000000000 2460.399660000000 0.000000000000 0.000000000000 3222.000000000000 -100.834816000000 -2460.399660000000 0.000000000000 0.000000000000 -5746.304200000000 -100.834816000000 10919.927700000000 150.178497000000 -4570.076170000000 5746.304200000000 0.000000000000 -2460.399660000000 150.178497000000 12733.399400000000 300.477600000000 100.834816000000 2460.399660000000 0.000000000000 -4570.076170000000 300.477600000000 2171.542720000000 13 19 60 4715.000000000000 0.000000000000 0.000000000000 0.000000000000 9156.117190000001 1075.338620000000 0.000000000000 4715.000000000000 0.000000000000 -9156.117190000001 0.000000000000 2985.391360000000 0.000000000000 0.000000000000 4715.000000000000 -1075.338620000000 -2985.391360000000 0.000000000000 0.000000000000 -9156.117190000001 -1075.338620000000 19185.953099999999 840.112915000000 -5877.023930000000 9156.117190000001 0.000000000000 -2985.391360000000 840.112915000000 20604.248000000000 2389.645260000000 1075.338620000000 2985.391360000000 0.000000000000 -5877.023930000000 2389.645260000000 2824.640380000000 13 25 60 4841.000000000000 0.000000000000 0.000000000000 0.000000000000 9800.745120000000 1198.614500000000 0.000000000000 4841.000000000000 0.000000000000 -9800.745120000000 0.000000000000 3673.100830000000 0.000000000000 0.000000000000 4841.000000000000 -1198.614500000000 -3673.100830000000 0.000000000000 0.000000000000 -9800.745120000000 -1198.614500000000 20882.609400000001 831.973572000000 -7367.991210000000 9800.745120000000 0.000000000000 -3673.100830000000 831.973572000000 22913.906299999999 2533.641850000000 1198.614500000000 3673.100830000000 0.000000000000 -7367.991210000000 2533.641850000000 3856.229740000000 13 30 60 4811.000000000000 0.000000000000 0.000000000000 0.000000000000 8576.104490000000 717.437622000000 0.000000000000 4811.000000000000 0.000000000000 -8576.104490000000 0.000000000000 -2680.777340000000 0.000000000000 0.000000000000 4811.000000000000 -717.437622000000 2680.777340000000 0.000000000000 0.000000000000 -8576.104490000000 -717.437622000000 16666.710899999998 -539.761902000000 4793.890620000000 8576.104490000000 0.000000000000 2680.777340000000 -539.761902000000 17413.462899999999 1764.313230000000 717.437622000000 -2680.777340000000 0.000000000000 4793.890620000000 1764.313230000000 2581.324950000000 13 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8142.696290000000 -844.593811000000 0.000000000000 5000.000000000000 0.000000000000 -8142.696290000000 0.000000000000 -2035.291630000000 0.000000000000 0.000000000000 5000.000000000000 844.593811000000 2035.291630000000 0.000000000000 0.000000000000 -8142.696290000000 844.593811000000 14081.002000000000 294.602600000000 3371.927000000000 8142.696290000000 0.000000000000 2035.291630000000 294.602600000000 14702.369100000000 -1307.632200000000 -844.593811000000 -2035.291630000000 0.000000000000 3371.927000000000 -1307.632200000000 1634.931760000000 13 32 60 2918.000000000000 0.000000000000 0.000000000000 0.000000000000 3909.759770000000 -680.189636000000 0.000000000000 2918.000000000000 0.000000000000 -3909.759770000000 0.000000000000 -915.383850000000 0.000000000000 0.000000000000 2918.000000000000 680.189636000000 915.383850000000 0.000000000000 0.000000000000 -3909.759770000000 680.189636000000 5690.868650000000 206.791489000000 1459.888060000000 3909.759770000000 0.000000000000 915.383850000000 206.791489000000 6218.232910000000 -920.830750000000 -680.189636000000 -915.383850000000 0.000000000000 1459.888060000000 -920.830750000000 1022.061340000000 13 36 60 1179.000000000000 0.000000000000 0.000000000000 0.000000000000 2184.259770000000 282.849518000000 0.000000000000 1179.000000000000 0.000000000000 -2184.259770000000 0.000000000000 892.033752000000 0.000000000000 0.000000000000 1179.000000000000 -282.849518000000 -892.033752000000 0.000000000000 0.000000000000 -2184.259770000000 -282.849518000000 4180.554690000000 217.442825000000 -1656.837040000000 2184.259770000000 0.000000000000 -892.033752000000 217.442825000000 4767.915530000000 527.689148000000 282.849518000000 892.033752000000 0.000000000000 -1656.837040000000 527.689148000000 783.659363000000 13 37 60 4773.000000000000 0.000000000000 0.000000000000 0.000000000000 8549.947270000001 190.104080000000 0.000000000000 4773.000000000000 0.000000000000 -8549.947270000001 0.000000000000 2614.529790000000 0.000000000000 0.000000000000 4773.000000000000 -190.104080000000 -2614.529790000000 0.000000000000 0.000000000000 -8549.947270000001 -190.104080000000 16806.300800000001 331.360382000000 -4897.638180000000 8549.947270000001 0.000000000000 -2614.529790000000 331.360382000000 18102.248000000000 615.396912000000 190.104080000000 2614.529790000000 0.000000000000 -4897.638180000000 615.396912000000 2058.927000000000 13 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9043.792970000000 165.934235000000 0.000000000000 5000.000000000000 0.000000000000 -9043.792970000000 0.000000000000 2815.177250000000 0.000000000000 0.000000000000 5000.000000000000 -165.934235000000 -2815.177250000000 0.000000000000 0.000000000000 -9043.792970000000 -165.934235000000 17643.822300000000 249.319031000000 -5289.427250000000 9043.792970000000 0.000000000000 -2815.177250000000 249.319031000000 19182.253900000000 504.843262000000 165.934235000000 2815.177250000000 0.000000000000 -5289.427250000000 504.843262000000 2102.024170000000 13 39 60 4213.000000000000 0.000000000000 0.000000000000 0.000000000000 7689.275390000000 538.670410000000 0.000000000000 4213.000000000000 0.000000000000 -7689.275390000000 0.000000000000 2554.324460000000 0.000000000000 0.000000000000 4213.000000000000 -538.670410000000 -2554.324460000000 0.000000000000 0.000000000000 -7689.275390000000 -538.670410000000 15444.671899999999 532.681335000000 -4900.163570000000 7689.275390000000 0.000000000000 -2554.324460000000 532.681335000000 16661.509800000000 1377.464720000000 538.670410000000 2554.324460000000 0.000000000000 -4900.163570000000 1377.464720000000 2209.222410000000 13 46 60 3931.000000000000 0.000000000000 0.000000000000 0.000000000000 8297.574220000000 2338.851320000000 0.000000000000 3931.000000000000 0.000000000000 -8297.574220000000 0.000000000000 2131.553710000000 0.000000000000 0.000000000000 3931.000000000000 -2338.851320000000 -2131.553710000000 0.000000000000 0.000000000000 -8297.574220000000 -2338.851320000000 19218.363300000001 1252.734860000000 -4359.174800000000 8297.574220000000 0.000000000000 -2131.553710000000 1252.734860000000 19249.607400000001 5046.462890000000 2338.851320000000 2131.553710000000 0.000000000000 -4359.174800000000 5046.462890000000 3107.791500000000 13 47 60 1313.000000000000 0.000000000000 0.000000000000 0.000000000000 2729.743410000000 869.935547000000 0.000000000000 1313.000000000000 0.000000000000 -2729.743410000000 0.000000000000 1032.569700000000 0.000000000000 0.000000000000 1313.000000000000 -869.935547000000 -1032.569700000000 0.000000000000 0.000000000000 -2729.743410000000 -869.935547000000 6330.334470000000 676.500732000000 -2125.317380000000 2729.743410000000 0.000000000000 -1032.569700000000 676.500732000000 6606.424320000000 1837.521360000000 869.935547000000 1032.569700000000 0.000000000000 -2125.317380000000 1837.521360000000 1489.754150000000 13 59 60 3442.000000000000 0.000000000000 0.000000000000 0.000000000000 6727.937500000000 252.053955000000 0.000000000000 3442.000000000000 0.000000000000 -6727.937500000000 0.000000000000 2520.331540000000 0.000000000000 0.000000000000 3442.000000000000 -252.053955000000 -2520.331540000000 0.000000000000 0.000000000000 -6727.937500000000 -252.053955000000 13471.326200000000 187.457108000000 -4930.149410000000 6727.937500000000 0.000000000000 -2520.331540000000 187.457108000000 15217.888700000000 451.408966000000 252.053955000000 2520.331540000000 0.000000000000 -4930.149410000000 451.408966000000 2054.968750000000 14 16 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7855.147950000000 336.544952000000 0.000000000000 5000.000000000000 0.000000000000 -7855.147950000000 0.000000000000 5032.456540000000 0.000000000000 0.000000000000 5000.000000000000 -336.544952000000 -5032.456540000000 0.000000000000 0.000000000000 -7855.147950000000 -336.544952000000 13024.980500000000 472.716431000000 -7852.167480000000 7855.147950000000 0.000000000000 -5032.456540000000 472.716431000000 18201.929700000001 477.099884000000 336.544952000000 5032.456540000000 0.000000000000 -7852.167480000000 477.099884000000 5626.366210000000 14 17 60 3898.000000000000 0.000000000000 0.000000000000 0.000000000000 5966.753420000000 339.094086000000 0.000000000000 3898.000000000000 0.000000000000 -5966.753420000000 0.000000000000 4590.413090000000 0.000000000000 0.000000000000 3898.000000000000 -339.094086000000 -4590.413090000000 0.000000000000 0.000000000000 -5966.753420000000 -339.094086000000 9452.913090000000 450.590057000000 -7042.224120000000 5966.753420000000 0.000000000000 -4590.413090000000 450.590057000000 14846.724600000000 497.489105000000 339.094086000000 4590.413090000000 0.000000000000 -7042.224120000000 497.489105000000 5654.242190000000 14 18 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7936.151860000000 502.802307000000 0.000000000000 5000.000000000000 0.000000000000 -7936.151860000000 0.000000000000 4717.294920000000 0.000000000000 0.000000000000 5000.000000000000 -502.802307000000 -4717.294920000000 0.000000000000 0.000000000000 -7936.151860000000 -502.802307000000 13231.632799999999 510.735535000000 -7503.662600000000 7936.151860000000 0.000000000000 -4717.294920000000 510.735535000000 17716.134800000000 846.424194000000 502.802307000000 4717.294920000000 0.000000000000 -7503.662600000000 846.424194000000 4967.769040000000 14 20 60 2213.000000000000 0.000000000000 0.000000000000 0.000000000000 3379.734620000000 513.517273000000 0.000000000000 2213.000000000000 0.000000000000 -3379.734620000000 0.000000000000 2182.750980000000 0.000000000000 0.000000000000 2213.000000000000 -513.517273000000 -2182.750980000000 0.000000000000 0.000000000000 -3379.734620000000 -513.517273000000 5428.372070000000 514.514954000000 -3319.360840000000 3379.734620000000 0.000000000000 -2182.750980000000 514.514954000000 7499.708500000000 807.291077000000 513.517273000000 2182.750980000000 0.000000000000 -3319.360840000000 807.291077000000 2416.648440000000 14 30 60 3916.000000000000 0.000000000000 0.000000000000 0.000000000000 5877.745610000000 14.615234400000 0.000000000000 3916.000000000000 0.000000000000 -5877.745610000000 0.000000000000 -2060.591060000000 0.000000000000 0.000000000000 3916.000000000000 -14.615234400000 2060.591060000000 0.000000000000 0.000000000000 -5877.745610000000 -14.615234400000 9490.943359999999 -158.748413000000 3150.222410000000 5877.745610000000 0.000000000000 2060.591060000000 -158.748413000000 10227.724600000000 231.782104000000 14.615234400000 -2060.591060000000 0.000000000000 3150.222410000000 231.782104000000 1654.693850000000 14 31 60 3360.000000000000 0.000000000000 0.000000000000 0.000000000000 4787.123050000000 -593.671021000000 0.000000000000 3360.000000000000 0.000000000000 -4787.123050000000 0.000000000000 -1411.827270000000 0.000000000000 0.000000000000 3360.000000000000 593.671021000000 1411.827270000000 0.000000000000 0.000000000000 -4787.123050000000 593.671021000000 7181.568850000000 246.775620000000 2035.426390000000 4787.123050000000 0.000000000000 1411.827270000000 246.775620000000 7602.972170000000 -854.612061000000 -593.671021000000 -1411.827270000000 0.000000000000 2035.426390000000 -854.612061000000 920.889282000000 14 32 60 1251.000000000000 0.000000000000 0.000000000000 0.000000000000 1464.916260000000 -258.395294000000 0.000000000000 1251.000000000000 0.000000000000 -1464.916260000000 0.000000000000 -408.209686000000 0.000000000000 0.000000000000 1251.000000000000 258.395294000000 408.209686000000 0.000000000000 0.000000000000 -1464.916260000000 258.395294000000 1836.822390000000 80.998359700000 551.023254000000 1464.916260000000 0.000000000000 408.209686000000 80.998359700000 2092.687010000000 -307.649261000000 -258.395294000000 -408.209686000000 0.000000000000 551.023254000000 -307.649261000000 394.871918000000 14 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7590.525880000000 690.797791000000 0.000000000000 5000.000000000000 0.000000000000 -7590.525880000000 0.000000000000 4569.844730000000 0.000000000000 0.000000000000 5000.000000000000 -690.797791000000 -4569.844730000000 0.000000000000 0.000000000000 -7590.525880000000 -690.797791000000 12305.168900000001 588.202942000000 -6960.995610000000 7590.525880000000 0.000000000000 -4569.844730000000 588.202942000000 16516.642599999999 1164.871460000000 690.797791000000 4569.844730000000 0.000000000000 -6960.995610000000 1164.871460000000 4861.072270000000 14 45 60 4536.000000000000 0.000000000000 0.000000000000 0.000000000000 8543.292970000000 2435.889650000000 0.000000000000 4536.000000000000 0.000000000000 -8543.292970000000 0.000000000000 -244.044876000000 0.000000000000 0.000000000000 4536.000000000000 -2435.889650000000 244.044876000000 0.000000000000 0.000000000000 -8543.292970000000 -2435.889650000000 17726.064500000000 -354.922699000000 746.519531000000 8543.292970000000 0.000000000000 244.044876000000 -354.922699000000 17503.312500000000 4708.087400000000 2435.889650000000 -244.044876000000 0.000000000000 746.519531000000 4708.087400000000 2729.918210000000 14 46 60 1903.000000000000 0.000000000000 0.000000000000 0.000000000000 3321.066410000000 911.915771000000 0.000000000000 1903.000000000000 0.000000000000 -3321.066410000000 0.000000000000 836.689331000000 0.000000000000 0.000000000000 1903.000000000000 -911.915771000000 -836.689331000000 0.000000000000 0.000000000000 -3321.066410000000 -911.915771000000 6337.809080000000 361.477448000000 -1364.051150000000 3321.066410000000 0.000000000000 -836.689331000000 361.477448000000 6541.858890000000 1632.256350000000 911.915771000000 836.689331000000 0.000000000000 -1364.051150000000 1632.256350000000 1158.416380000000 14 47 60 849.000000000000 0.000000000000 0.000000000000 0.000000000000 1434.600830000000 421.616852000000 0.000000000000 849.000000000000 0.000000000000 -1434.600830000000 0.000000000000 641.955627000000 0.000000000000 0.000000000000 849.000000000000 -421.616852000000 -641.955627000000 0.000000000000 0.000000000000 -1434.600830000000 -421.616852000000 2712.305420000000 276.549469000000 -1017.585820000000 1434.600830000000 0.000000000000 -641.955627000000 276.549469000000 3099.138430000000 747.166260000000 421.616852000000 641.955627000000 0.000000000000 -1017.585820000000 747.166260000000 855.537537000000 14 52 60 1526.000000000000 0.000000000000 0.000000000000 0.000000000000 2346.775880000000 564.202881000000 0.000000000000 1526.000000000000 0.000000000000 -2346.775880000000 0.000000000000 1649.159910000000 0.000000000000 0.000000000000 1526.000000000000 -564.202881000000 -1649.159910000000 0.000000000000 0.000000000000 -2346.775880000000 -564.202881000000 3897.714600000000 576.624695000000 -2489.253660000000 2346.775880000000 0.000000000000 -1649.159910000000 576.624695000000 5512.102050000000 900.707642000000 564.202881000000 1649.159910000000 0.000000000000 -2489.253660000000 900.707642000000 2103.420410000000 15 21 60 3642.000000000000 0.000000000000 0.000000000000 0.000000000000 7058.250980000000 2072.302490000000 0.000000000000 3642.000000000000 0.000000000000 -7058.250980000000 0.000000000000 4311.093750000000 0.000000000000 0.000000000000 3642.000000000000 -2072.302490000000 -4311.093750000000 0.000000000000 0.000000000000 -7058.250980000000 -2072.302490000000 16056.448200000001 2499.778560000000 -8458.541990000000 7058.250980000000 0.000000000000 -4311.093750000000 2499.778560000000 19710.173800000000 4406.974120000000 2072.302490000000 4311.093750000000 0.000000000000 -8458.541990000000 4406.974120000000 6773.690920000000 15 24 60 3953.000000000000 0.000000000000 0.000000000000 0.000000000000 8337.384770000001 1585.243770000000 0.000000000000 3953.000000000000 0.000000000000 -8337.384770000001 0.000000000000 5001.201660000000 0.000000000000 0.000000000000 3953.000000000000 -1585.243770000000 -5001.201660000000 0.000000000000 0.000000000000 -8337.384770000001 -1585.243770000000 18959.132799999999 1918.564090000000 -10567.255900000000 8337.384770000001 0.000000000000 -5001.201660000000 1918.564090000000 24317.861300000000 3393.318360000000 1585.243770000000 5001.201660000000 0.000000000000 -10567.255900000000 3393.318360000000 7509.299320000000 15 28 60 3773.000000000000 0.000000000000 0.000000000000 0.000000000000 6216.144530000000 -920.153198000000 0.000000000000 3773.000000000000 0.000000000000 -6216.144530000000 0.000000000000 -1383.323610000000 0.000000000000 0.000000000000 3773.000000000000 920.153198000000 1383.323610000000 0.000000000000 0.000000000000 -6216.144530000000 920.153198000000 11389.123000000000 344.629822000000 2771.683590000000 6216.144530000000 0.000000000000 1383.323610000000 344.629822000000 12052.869100000000 -1583.593020000000 -920.153198000000 -1383.323610000000 0.000000000000 2771.683590000000 -1583.593020000000 1796.734860000000 15 29 60 1342.000000000000 0.000000000000 0.000000000000 0.000000000000 2481.168460000000 -471.877289000000 0.000000000000 1342.000000000000 0.000000000000 -2481.168460000000 0.000000000000 -1086.500850000000 0.000000000000 0.000000000000 1342.000000000000 471.877289000000 1086.500850000000 0.000000000000 0.000000000000 -2481.168460000000 471.877289000000 4932.586430000000 391.232056000000 2022.743160000000 2481.168460000000 0.000000000000 1086.500850000000 391.232056000000 5523.496580000000 -891.837708000000 -471.877289000000 -1086.500850000000 0.000000000000 2022.743160000000 -891.837708000000 1210.577390000000 15 35 60 2537.000000000000 0.000000000000 0.000000000000 0.000000000000 4243.298830000000 1213.979980000000 0.000000000000 2537.000000000000 0.000000000000 -4243.298830000000 0.000000000000 2046.000370000000 0.000000000000 0.000000000000 2537.000000000000 -1213.979980000000 -2046.000370000000 0.000000000000 0.000000000000 -4243.298830000000 -1213.979980000000 8166.586910000000 1009.140500000000 -3562.748540000000 4243.298830000000 0.000000000000 -2046.000370000000 1009.140500000000 9463.546880000000 2201.577640000000 1213.979980000000 2046.000370000000 0.000000000000 -3562.748540000000 2201.577640000000 2802.941410000000 15 40 60 1056.000000000000 0.000000000000 0.000000000000 0.000000000000 1778.089600000000 93.301582300000 0.000000000000 1056.000000000000 0.000000000000 -1778.089600000000 0.000000000000 -596.545532000000 0.000000000000 0.000000000000 1056.000000000000 -93.301582300000 596.545532000000 0.000000000000 0.000000000000 -1778.089600000000 -93.301582300000 3334.578130000000 -40.886123700000 1049.086300000000 1778.089600000000 0.000000000000 596.545532000000 -40.886123700000 3505.382080000000 175.028458000000 93.301582300000 -596.545532000000 0.000000000000 1049.086300000000 175.028458000000 615.770264000000 15 41 60 3833.000000000000 0.000000000000 0.000000000000 0.000000000000 6631.839840000000 563.743286000000 0.000000000000 3833.000000000000 0.000000000000 -6631.839840000000 0.000000000000 -2444.189940000000 0.000000000000 0.000000000000 3833.000000000000 -563.743286000000 2444.189940000000 0.000000000000 0.000000000000 -6631.839840000000 -563.743286000000 11735.865200000000 -314.424500000000 4262.436040000000 6631.839840000000 0.000000000000 2444.189940000000 -314.424500000000 13206.794900000001 922.724304000000 563.743286000000 -2444.189940000000 0.000000000000 4262.436040000000 922.724304000000 1886.475340000000 15 42 60 3402.000000000000 0.000000000000 0.000000000000 0.000000000000 5832.454100000000 754.095886000000 0.000000000000 3402.000000000000 0.000000000000 -5832.454100000000 0.000000000000 -2097.042720000000 0.000000000000 0.000000000000 3402.000000000000 -754.095886000000 2097.042720000000 0.000000000000 0.000000000000 -5832.454100000000 -754.095886000000 10330.908200000000 -441.141418000000 3601.018800000000 5832.454100000000 0.000000000000 2097.042720000000 -441.141418000000 11413.802700000000 1281.362180000000 754.095886000000 -2097.042720000000 0.000000000000 3601.018800000000 1281.362180000000 1678.550780000000 15 43 60 2773.000000000000 0.000000000000 0.000000000000 0.000000000000 4674.944820000000 846.690430000000 0.000000000000 2773.000000000000 0.000000000000 -4674.944820000000 0.000000000000 -1757.836550000000 0.000000000000 0.000000000000 2773.000000000000 -846.690430000000 1757.836550000000 0.000000000000 0.000000000000 -4674.944820000000 -846.690430000000 8278.763670000000 -500.396729000000 2959.913570000000 4674.944820000000 0.000000000000 1757.836550000000 -500.396729000000 9098.500980000001 1453.036380000000 846.690430000000 -1757.836550000000 0.000000000000 2959.913570000000 1453.036380000000 1540.986940000000 15 44 60 2761.000000000000 0.000000000000 0.000000000000 0.000000000000 4597.471190000000 946.155273000000 0.000000000000 2761.000000000000 0.000000000000 -4597.471190000000 0.000000000000 -1609.555420000000 0.000000000000 0.000000000000 2761.000000000000 -946.155273000000 1609.555420000000 0.000000000000 0.000000000000 -4597.471190000000 -946.155273000000 8119.518550000000 -511.140747000000 2678.435300000000 4597.471190000000 0.000000000000 1609.555420000000 -511.140747000000 8712.715819999999 1606.171020000000 946.155273000000 -1609.555420000000 0.000000000000 2678.435300000000 1606.171020000000 1441.928590000000 15 45 60 2658.000000000000 0.000000000000 0.000000000000 0.000000000000 4349.671880000000 1188.734010000000 0.000000000000 2658.000000000000 0.000000000000 -4349.671880000000 0.000000000000 -944.101135000000 0.000000000000 0.000000000000 2658.000000000000 -1188.734010000000 944.101135000000 0.000000000000 0.000000000000 -4349.671880000000 -1188.734010000000 7792.786620000000 -328.872528000000 1548.673950000000 4349.671880000000 0.000000000000 944.101135000000 -328.872528000000 7707.000000000000 1975.972050000000 1188.734010000000 -944.101135000000 0.000000000000 1548.673950000000 1975.972050000000 1202.697020000000 15 46 60 2336.000000000000 0.000000000000 0.000000000000 0.000000000000 3819.620360000000 1250.004150000000 0.000000000000 2336.000000000000 0.000000000000 -3819.620360000000 0.000000000000 -280.276459000000 0.000000000000 0.000000000000 2336.000000000000 -1250.004150000000 280.276459000000 0.000000000000 0.000000000000 -3819.620360000000 -1250.004150000000 7021.393070000000 -89.820205700000 457.261383000000 3819.620360000000 0.000000000000 280.276459000000 -89.820205700000 6580.770510000000 2074.249760000000 1250.004150000000 -280.276459000000 0.000000000000 457.261383000000 2074.249760000000 1061.765260000000 15 47 60 1800.000000000000 0.000000000000 0.000000000000 0.000000000000 3066.081300000000 1126.181520000000 0.000000000000 1800.000000000000 0.000000000000 -3066.081300000000 0.000000000000 414.397156000000 0.000000000000 0.000000000000 1800.000000000000 -1126.181520000000 -414.397156000000 0.000000000000 0.000000000000 -3066.081300000000 -1126.181520000000 6049.567870000000 319.523010000000 -754.585938000000 3066.081300000000 0.000000000000 -414.397156000000 319.523010000000 5832.500490000000 1968.024050000000 1126.181520000000 414.397156000000 0.000000000000 -754.585938000000 1968.024050000000 1335.365360000000 15 48 60 2266.000000000000 0.000000000000 0.000000000000 0.000000000000 3949.040040000000 1424.056150000000 0.000000000000 2266.000000000000 0.000000000000 -3949.040040000000 0.000000000000 1169.604370000000 0.000000000000 0.000000000000 2266.000000000000 -1424.056150000000 -1169.604370000000 0.000000000000 0.000000000000 -3949.040040000000 -1424.056150000000 7961.411620000000 835.228394000000 -2197.829350000000 3949.040040000000 0.000000000000 -1169.604370000000 835.228394000000 8206.423830000000 2555.414310000000 1424.056150000000 1169.604370000000 0.000000000000 -2197.829350000000 2555.414310000000 2207.238530000000 15 49 60 1517.000000000000 0.000000000000 0.000000000000 0.000000000000 2702.039550000000 995.859619000000 0.000000000000 1517.000000000000 0.000000000000 -2702.039550000000 0.000000000000 1001.281130000000 0.000000000000 0.000000000000 1517.000000000000 -995.859619000000 -1001.281130000000 0.000000000000 0.000000000000 -2702.039550000000 -995.859619000000 5585.640630000000 702.935547000000 -1887.357540000000 2702.039550000000 0.000000000000 -1001.281130000000 702.935547000000 5926.769040000000 1817.866580000000 995.859619000000 1001.281130000000 0.000000000000 -1887.357540000000 1817.866580000000 1749.841550000000 15 50 60 1849.000000000000 0.000000000000 0.000000000000 0.000000000000 3237.273190000000 1266.790890000000 0.000000000000 1849.000000000000 0.000000000000 -3237.273190000000 0.000000000000 879.252319000000 0.000000000000 0.000000000000 1849.000000000000 -1266.790890000000 -879.252319000000 0.000000000000 0.000000000000 -3237.273190000000 -1266.790890000000 6665.943850000000 642.210510000000 -1597.655880000000 3237.273190000000 0.000000000000 -879.252319000000 642.210510000000 6503.555660000000 2269.594970000000 1266.790890000000 879.252319000000 0.000000000000 -1597.655880000000 2269.594970000000 1705.154660000000 15 51 60 1227.000000000000 0.000000000000 0.000000000000 0.000000000000 2096.395260000000 774.992920000000 0.000000000000 1227.000000000000 0.000000000000 -2096.395260000000 0.000000000000 95.786621100000 0.000000000000 0.000000000000 1227.000000000000 -774.992920000000 -95.786621100000 0.000000000000 0.000000000000 -2096.395260000000 -774.992920000000 4132.914550000000 54.537162800000 -145.733963000000 2096.395260000000 0.000000000000 -95.786621100000 54.537162800000 3742.305660000000 1341.423580000000 774.992920000000 95.786621100000 0.000000000000 -145.733963000000 1341.423580000000 675.028748000000 15 52 60 2648.000000000000 0.000000000000 0.000000000000 0.000000000000 4614.676270000000 1801.524410000000 0.000000000000 2648.000000000000 0.000000000000 -4614.676270000000 0.000000000000 1547.995360000000 0.000000000000 0.000000000000 2648.000000000000 -1801.524410000000 -1547.995360000000 0.000000000000 0.000000000000 -4614.676270000000 -1801.524410000000 9450.697270000001 1134.513670000000 -2813.716550000000 4614.676270000000 0.000000000000 -1547.995360000000 1134.513670000000 9688.859380000000 3200.548340000000 1801.524410000000 1547.995360000000 0.000000000000 -2813.716550000000 3200.548340000000 2870.374270000000 15 53 60 2830.000000000000 0.000000000000 0.000000000000 0.000000000000 4876.083500000000 1835.145020000000 0.000000000000 2830.000000000000 0.000000000000 -4876.083500000000 0.000000000000 1668.250730000000 0.000000000000 0.000000000000 2830.000000000000 -1835.145020000000 -1668.250730000000 0.000000000000 0.000000000000 -4876.083500000000 -1835.145020000000 9791.160159999999 1158.598750000000 -3038.848140000000 4876.083500000000 0.000000000000 -1668.250730000000 1158.598750000000 10094.382799999999 3224.246090000000 1835.145020000000 1668.250730000000 0.000000000000 -3038.848140000000 3224.246090000000 2881.820560000000 15 54 60 4124.000000000000 0.000000000000 0.000000000000 0.000000000000 5877.178220000000 986.735107000000 0.000000000000 4124.000000000000 0.000000000000 -5877.178220000000 0.000000000000 3525.047610000000 0.000000000000 0.000000000000 4124.000000000000 -986.735107000000 -3525.047610000000 0.000000000000 0.000000000000 -5877.178220000000 -986.735107000000 10220.390600000001 956.773438000000 -5306.200200000000 5877.178220000000 0.000000000000 -3525.047610000000 956.773438000000 12835.758800000000 2025.514890000000 986.735107000000 3525.047610000000 0.000000000000 -5306.200200000000 2025.514890000000 4274.502930000000 15 55 60 2901.000000000000 0.000000000000 0.000000000000 0.000000000000 3045.933590000000 -248.754120000000 0.000000000000 2901.000000000000 0.000000000000 -3045.933590000000 0.000000000000 2422.993900000000 0.000000000000 0.000000000000 2901.000000000000 248.754120000000 -2422.993900000000 0.000000000000 0.000000000000 -3045.933590000000 248.754120000000 3749.933350000000 -115.887611000000 -2805.145020000000 3045.933590000000 0.000000000000 -2422.993900000000 -115.887611000000 6026.948240000000 -148.849289000000 -248.754120000000 2422.993900000000 0.000000000000 -2805.145020000000 -148.849289000000 2478.819090000000 15 56 60 2503.000000000000 0.000000000000 0.000000000000 0.000000000000 2379.789550000000 -361.766968000000 0.000000000000 2503.000000000000 0.000000000000 -2379.789550000000 0.000000000000 1726.908690000000 0.000000000000 0.000000000000 2503.000000000000 361.766968000000 -1726.908690000000 0.000000000000 0.000000000000 -2379.789550000000 361.766968000000 2573.666500000000 -227.197784000000 -1778.683230000000 2379.789550000000 0.000000000000 -1726.908690000000 -227.197784000000 3904.209960000000 -306.390930000000 -361.766968000000 1726.908690000000 0.000000000000 -1778.683230000000 -306.390930000000 1488.056760000000 15 57 60 2867.000000000000 0.000000000000 0.000000000000 0.000000000000 2795.863280000000 -379.509827000000 0.000000000000 2867.000000000000 0.000000000000 -2795.863280000000 0.000000000000 1826.844850000000 0.000000000000 0.000000000000 2867.000000000000 379.509827000000 -1826.844850000000 0.000000000000 0.000000000000 -2795.863280000000 379.509827000000 3169.769040000000 -223.647354000000 -1944.086550000000 2795.863280000000 0.000000000000 -1826.844850000000 -223.647354000000 4451.525880000000 -295.317413000000 -379.509827000000 1826.844850000000 0.000000000000 -1944.086550000000 -295.317413000000 1453.727420000000 15 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7023.128910000000 557.492554000000 0.000000000000 5000.000000000000 0.000000000000 -7023.128910000000 0.000000000000 4032.322270000000 0.000000000000 0.000000000000 5000.000000000000 -557.492554000000 -4032.322270000000 0.000000000000 0.000000000000 -7023.128910000000 -557.492554000000 12043.068400000000 814.049011000000 -6291.115230000000 7023.128910000000 0.000000000000 -4032.322270000000 814.049011000000 15341.512699999999 1499.444340000000 557.492554000000 4032.322270000000 0.000000000000 -6291.115230000000 1499.444340000000 4577.639650000000 16 27 60 4882.000000000000 0.000000000000 0.000000000000 0.000000000000 6163.311520000000 -134.419586000000 0.000000000000 4882.000000000000 0.000000000000 -6163.311520000000 0.000000000000 -263.278564000000 0.000000000000 0.000000000000 4882.000000000000 134.419586000000 263.278564000000 0.000000000000 0.000000000000 -6163.311520000000 134.419586000000 8876.636720000000 -308.866272000000 910.508362000000 6163.311520000000 0.000000000000 263.278564000000 -308.866272000000 9366.551760000000 173.126312000000 -134.419586000000 -263.278564000000 0.000000000000 910.508362000000 173.126312000000 1219.436890000000 16 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5700.988280000000 -164.615311000000 0.000000000000 5000.000000000000 0.000000000000 -5700.988280000000 0.000000000000 3339.789550000000 0.000000000000 0.000000000000 5000.000000000000 164.615311000000 -3339.789550000000 0.000000000000 0.000000000000 -5700.988280000000 164.615311000000 6992.789060000000 243.039917000000 -4193.432130000000 5700.988280000000 0.000000000000 -3339.789550000000 243.039917000000 10125.390600000001 41.366054500000 -164.615311000000 3339.789550000000 0.000000000000 -4193.432130000000 41.366054500000 3517.657470000000 16 48 60 3235.000000000000 0.000000000000 0.000000000000 0.000000000000 6702.770020000000 2040.490110000000 0.000000000000 3235.000000000000 0.000000000000 -6702.770020000000 0.000000000000 -431.063324000000 0.000000000000 0.000000000000 3235.000000000000 -2040.490110000000 431.063324000000 0.000000000000 0.000000000000 -6702.770020000000 -2040.490110000000 16128.749000000000 -173.513397000000 304.180450000000 6702.770020000000 0.000000000000 431.063324000000 -173.513397000000 15204.558600000000 4341.323240000000 2040.490110000000 -431.063324000000 0.000000000000 304.180450000000 4341.323240000000 2152.367920000000 16 49 60 3756.000000000000 0.000000000000 0.000000000000 0.000000000000 8323.963870000000 2487.867430000000 0.000000000000 3756.000000000000 0.000000000000 -8323.963870000000 0.000000000000 314.952271000000 0.000000000000 0.000000000000 3756.000000000000 -2487.867430000000 -314.952271000000 0.000000000000 0.000000000000 -8323.963870000000 -2487.867430000000 21255.111300000000 393.544159000000 -1537.919070000000 8323.963870000000 0.000000000000 -314.952271000000 393.544159000000 20269.687500000000 5667.697270000000 2487.867430000000 314.952271000000 0.000000000000 -1537.919070000000 5667.697270000000 2826.502930000000 16 50 60 3359.000000000000 0.000000000000 0.000000000000 0.000000000000 6502.793460000000 1921.309570000000 0.000000000000 3359.000000000000 0.000000000000 -6502.793460000000 0.000000000000 -823.592773000000 0.000000000000 0.000000000000 3359.000000000000 -1921.309570000000 823.592773000000 0.000000000000 0.000000000000 -6502.793460000000 -1921.309570000000 14367.643599999999 -321.699860000000 1255.244750000000 6502.793460000000 0.000000000000 823.592773000000 -321.699860000000 13547.554700000001 3943.458980000000 1921.309570000000 -823.592773000000 0.000000000000 1255.244750000000 3943.458980000000 1876.128540000000 16 52 60 4314.000000000000 0.000000000000 0.000000000000 0.000000000000 8541.931640000001 2468.258060000000 0.000000000000 4314.000000000000 0.000000000000 -8541.931640000001 0.000000000000 -697.215088000000 0.000000000000 0.000000000000 4314.000000000000 -2468.258060000000 697.215088000000 0.000000000000 0.000000000000 -8541.931640000001 -2468.258060000000 19270.419900000001 -238.724411000000 859.452942000000 8541.931640000001 0.000000000000 697.215088000000 -238.724411000000 18189.083999999999 5103.486820000000 2468.258060000000 -697.215088000000 0.000000000000 859.452942000000 5103.486820000000 2426.317870000000 16 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7511.924800000000 -84.430908200000 0.000000000000 5000.000000000000 0.000000000000 -7511.924800000000 0.000000000000 3262.407470000000 0.000000000000 0.000000000000 5000.000000000000 84.430908200000 -3262.407470000000 0.000000000000 0.000000000000 -7511.924800000000 84.430908200000 14597.909200000000 225.468811000000 -5432.913570000000 7511.924800000000 0.000000000000 -3262.407470000000 225.468811000000 17365.283200000002 553.921936000000 -84.430908200000 3262.407470000000 0.000000000000 -5432.913570000000 553.921936000000 3233.032960000000 17 26 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8652.875000000000 -754.133362000000 0.000000000000 5000.000000000000 0.000000000000 -8652.875000000000 0.000000000000 -2693.624510000000 0.000000000000 0.000000000000 5000.000000000000 754.133362000000 2693.624510000000 0.000000000000 0.000000000000 -8652.875000000000 754.133362000000 17205.220700000002 4.624612330000 5140.424800000000 8652.875000000000 0.000000000000 2693.624510000000 4.624612330000 19326.531299999999 -1280.238770000000 -754.133362000000 -2693.624510000000 0.000000000000 5140.424800000000 -1280.238770000000 3356.986570000000 17 48 60 3555.000000000000 0.000000000000 0.000000000000 0.000000000000 7538.361820000000 959.658813000000 0.000000000000 3555.000000000000 0.000000000000 -7538.361820000000 0.000000000000 -3220.784180000000 0.000000000000 0.000000000000 3555.000000000000 -959.658813000000 3220.784180000000 0.000000000000 0.000000000000 -7538.361820000000 -959.658813000000 17625.056600000000 -980.320068000000 6384.376460000000 7538.361820000000 0.000000000000 3220.784180000000 -980.320068000000 20221.234400000001 1931.903930000000 959.658813000000 -3220.784180000000 0.000000000000 6384.376460000000 1931.903930000000 3749.171390000000 17 49 60 4848.000000000000 0.000000000000 0.000000000000 0.000000000000 11160.580099999999 1273.569460000000 0.000000000000 4848.000000000000 0.000000000000 -11160.580099999999 0.000000000000 -3769.256100000000 0.000000000000 0.000000000000 4848.000000000000 -1273.569460000000 3769.256100000000 0.000000000000 0.000000000000 -11160.580099999999 -1273.569460000000 28056.056600000000 -1119.498050000000 7878.259280000000 11160.580099999999 0.000000000000 3769.256100000000 -1119.498050000000 30758.906299999999 2750.560790000000 1273.569460000000 -3769.256100000000 0.000000000000 7878.259280000000 2750.560790000000 4122.755370000000 17 50 60 2431.000000000000 0.000000000000 0.000000000000 0.000000000000 4435.033200000000 553.354553000000 0.000000000000 2431.000000000000 0.000000000000 -4435.033200000000 0.000000000000 -2485.088130000000 0.000000000000 0.000000000000 2431.000000000000 -553.354553000000 2485.088130000000 0.000000000000 0.000000000000 -4435.033200000000 -553.354553000000 8690.017580000000 -618.938721000000 4449.194340000000 4435.033200000000 0.000000000000 2485.088130000000 -618.938721000000 11031.225600000000 1059.933590000000 553.354553000000 -2485.088130000000 0.000000000000 4449.194340000000 1059.933590000000 2912.824220000000 17 52 60 4154.000000000000 0.000000000000 0.000000000000 0.000000000000 8927.594730000001 447.121429000000 0.000000000000 4154.000000000000 0.000000000000 -8927.594730000001 0.000000000000 -3466.856930000000 0.000000000000 0.000000000000 4154.000000000000 -447.121429000000 3466.856930000000 0.000000000000 0.000000000000 -8927.594730000001 -447.121429000000 20777.791000000001 -601.451233000000 6977.040040000000 8927.594730000001 0.000000000000 3466.856930000000 -601.451233000000 23456.234400000001 685.884644000000 447.121429000000 -3466.856930000000 0.000000000000 6977.040040000000 685.884644000000 3739.777100000000 17 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11047.439500000000 161.770599000000 0.000000000000 5000.000000000000 0.000000000000 -11047.439500000000 0.000000000000 1171.789790000000 0.000000000000 0.000000000000 5000.000000000000 -161.770599000000 -1171.789790000000 0.000000000000 0.000000000000 -11047.439500000000 -161.770599000000 29534.445299999999 447.535339000000 -2932.936770000000 11047.439500000000 0.000000000000 -1171.789790000000 447.535339000000 29859.212899999999 1747.501830000000 161.770599000000 1171.789790000000 0.000000000000 -2932.936770000000 1747.501830000000 1951.968380000000 17 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10517.652300000000 -491.711243000000 0.000000000000 5000.000000000000 0.000000000000 -10517.652300000000 0.000000000000 891.260376000000 0.000000000000 0.000000000000 5000.000000000000 491.711243000000 -891.260376000000 0.000000000000 0.000000000000 -10517.652300000000 491.711243000000 26978.777300000002 542.085388000000 -2387.403320000000 10517.652300000000 0.000000000000 -891.260376000000 542.085388000000 27601.833999999999 47.109977700000 -491.711243000000 891.260376000000 0.000000000000 -2387.403320000000 47.109977700000 2000.799560000000 18 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15413.168000000000 2952.017090000000 0.000000000000 5000.000000000000 0.000000000000 -15413.168000000000 0.000000000000 3316.641850000000 0.000000000000 0.000000000000 5000.000000000000 -2952.017090000000 -3316.641850000000 0.000000000000 0.000000000000 -15413.168000000000 -2952.017090000000 50528.281199999998 2219.739010000000 -10409.331099999999 15413.168000000000 0.000000000000 -3316.641850000000 2219.739010000000 50945.722699999998 9196.589840000001 2952.017090000000 3316.641850000000 0.000000000000 -10409.331099999999 9196.589840000001 5349.630860000000 18 27 60 4876.000000000000 0.000000000000 0.000000000000 0.000000000000 6478.313960000000 -1656.231810000000 0.000000000000 4876.000000000000 0.000000000000 -6478.313960000000 0.000000000000 -1996.439940000000 0.000000000000 0.000000000000 4876.000000000000 1656.231810000000 1996.439940000000 0.000000000000 0.000000000000 -6478.313960000000 1656.231810000000 10324.220700000000 549.167908000000 3282.913570000000 6478.313960000000 0.000000000000 1996.439940000000 549.167908000000 11256.244100000000 -2044.153200000000 -1656.231810000000 -1996.439940000000 0.000000000000 3282.913570000000 -2044.153200000000 2290.359130000000 18 46 60 3429.000000000000 0.000000000000 0.000000000000 0.000000000000 6667.615230000000 1567.462520000000 0.000000000000 3429.000000000000 0.000000000000 -6667.615230000000 0.000000000000 -3875.444090000000 0.000000000000 0.000000000000 3429.000000000000 -1567.462520000000 3875.444090000000 0.000000000000 0.000000000000 -6667.615230000000 -1567.462520000000 14058.565399999999 -1829.286380000000 7476.127930000000 6667.615230000000 0.000000000000 3875.444090000000 -1829.286380000000 17603.037100000001 3127.312010000000 1567.462520000000 -3875.444090000000 0.000000000000 7476.127930000000 3127.312010000000 5531.829590000000 18 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10746.315399999999 2559.769530000000 0.000000000000 5000.000000000000 0.000000000000 -10746.315399999999 0.000000000000 -4212.793950000000 0.000000000000 0.000000000000 5000.000000000000 -2559.769530000000 4212.793950000000 0.000000000000 0.000000000000 -10746.315399999999 -2559.769530000000 25184.492200000001 -2147.549560000000 8688.656250000000 10746.315399999999 0.000000000000 4212.793950000000 -2147.549560000000 27552.009800000000 5637.604980000000 2559.769530000000 -4212.793950000000 0.000000000000 8688.656250000000 5637.604980000000 5703.541020000000 18 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11179.914100000000 2187.090330000000 0.000000000000 5000.000000000000 0.000000000000 -11179.914100000000 0.000000000000 -3631.168210000000 0.000000000000 0.000000000000 5000.000000000000 -2187.090330000000 3631.168210000000 0.000000000000 0.000000000000 -11179.914100000000 -2187.090330000000 27142.101600000002 -1724.526250000000 7384.177730000000 11179.914100000000 0.000000000000 3631.168210000000 -1724.526250000000 29337.367200000001 4847.372560000000 2187.090330000000 -3631.168210000000 0.000000000000 7384.177730000000 4847.372560000000 4944.935550000000 18 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11834.145500000001 1951.072510000000 0.000000000000 5000.000000000000 0.000000000000 -11834.145500000001 0.000000000000 -2888.181150000000 0.000000000000 0.000000000000 5000.000000000000 -1951.072510000000 2888.181150000000 0.000000000000 0.000000000000 -11834.145500000001 -1951.072510000000 30533.976600000002 -1526.024900000000 5490.630860000000 11834.145500000001 0.000000000000 2888.181150000000 -1526.024900000000 32621.312500000000 4308.076170000000 1951.072510000000 -2888.181150000000 0.000000000000 5490.630860000000 4308.076170000000 4598.031740000000 18 50 60 4375.000000000000 0.000000000000 0.000000000000 0.000000000000 9960.879880000000 1454.247560000000 0.000000000000 4375.000000000000 0.000000000000 -9960.879880000000 0.000000000000 -3044.079100000000 0.000000000000 0.000000000000 4375.000000000000 -1454.247560000000 3044.079100000000 0.000000000000 0.000000000000 -9960.879880000000 -1454.247560000000 24160.464800000002 -1021.433470000000 6311.578130000000 9960.879880000000 0.000000000000 3044.079100000000 -1021.433470000000 26181.601600000002 3390.469480000000 1454.247560000000 -3044.079100000000 0.000000000000 6311.578130000000 3390.469480000000 3581.746090000000 18 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11498.521500000001 1489.434690000000 0.000000000000 5000.000000000000 0.000000000000 -11498.521500000001 0.000000000000 -3303.003420000000 0.000000000000 0.000000000000 5000.000000000000 -1489.434690000000 3303.003420000000 0.000000000000 0.000000000000 -11498.521500000001 -1489.434690000000 28207.125000000000 -1117.565670000000 6750.062500000000 11498.521500000001 0.000000000000 3303.003420000000 -1117.565670000000 30512.492200000001 3395.628660000000 1489.434690000000 -3303.003420000000 0.000000000000 6750.062500000000 3395.628660000000 4091.859380000000 18 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8217.444340000000 -955.964661000000 0.000000000000 5000.000000000000 0.000000000000 -8217.444340000000 0.000000000000 1371.397950000000 0.000000000000 0.000000000000 5000.000000000000 955.964661000000 -1371.397950000000 0.000000000000 0.000000000000 -8217.444340000000 955.964661000000 17285.478500000001 142.192902000000 -3269.187500000000 8217.444340000000 0.000000000000 -1371.397950000000 142.192902000000 17953.687500000000 -711.327759000000 -955.964661000000 1371.397950000000 0.000000000000 -3269.187500000000 -711.327759000000 1788.048340000000 18 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7481.624020000000 -1280.634890000000 0.000000000000 5000.000000000000 0.000000000000 -7481.624020000000 0.000000000000 1137.086060000000 0.000000000000 0.000000000000 5000.000000000000 1280.634890000000 -1137.086060000000 0.000000000000 0.000000000000 -7481.624020000000 1280.634890000000 14343.747100000001 81.812553400000 -2840.126220000000 7481.624020000000 0.000000000000 -1137.086060000000 81.812553400000 15161.650400000000 -1337.938840000000 -1280.634890000000 1137.086060000000 0.000000000000 -2840.126220000000 -1337.938840000000 1888.412840000000 18 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9892.382809999999 -665.822632000000 0.000000000000 5000.000000000000 0.000000000000 -9892.382809999999 0.000000000000 306.294952000000 0.000000000000 0.000000000000 5000.000000000000 665.822632000000 -306.294952000000 0.000000000000 0.000000000000 -9892.382809999999 665.822632000000 23718.371100000000 78.194648700000 -768.033325000000 9892.382809999999 0.000000000000 -306.294952000000 78.194648700000 24080.931600000000 -442.571533000000 -665.822632000000 306.294952000000 0.000000000000 -768.033325000000 -442.571533000000 1153.465580000000 19 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14736.711900000000 3386.383540000000 0.000000000000 5000.000000000000 0.000000000000 -14736.711900000000 0.000000000000 5237.311520000000 0.000000000000 0.000000000000 5000.000000000000 -3386.383540000000 -5237.311520000000 0.000000000000 0.000000000000 -14736.711900000000 -3386.383540000000 46463.960899999998 3632.836910000000 -15482.414100000000 14736.711900000000 0.000000000000 -5237.311520000000 3632.836910000000 49395.421900000001 9872.049800000001 3386.383540000000 5237.311520000000 0.000000000000 -15482.414100000000 9872.049800000001 8472.249019999999 19 23 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14829.759800000000 3158.169920000000 0.000000000000 5000.000000000000 0.000000000000 -14829.759800000000 0.000000000000 5472.051760000000 0.000000000000 0.000000000000 5000.000000000000 -3158.169920000000 -5472.051760000000 0.000000000000 0.000000000000 -14829.759800000000 -3158.169920000000 46756.644500000002 3473.548100000000 -16329.275400000000 14829.759800000000 0.000000000000 -5472.051760000000 3473.548100000000 50492.062500000000 9250.051760000000 3158.169920000000 5472.051760000000 0.000000000000 -16329.275400000000 9250.051760000000 8662.636720000000 19 27 60 4949.000000000000 0.000000000000 0.000000000000 0.000000000000 8106.676270000000 -836.437561000000 0.000000000000 4949.000000000000 0.000000000000 -8106.676270000000 0.000000000000 -2959.693600000000 0.000000000000 0.000000000000 4949.000000000000 836.437561000000 2959.693600000000 0.000000000000 0.000000000000 -8106.676270000000 836.437561000000 15157.188500000000 359.200867000000 5705.317380000000 8106.676270000000 0.000000000000 2959.693600000000 359.200867000000 17518.886699999999 -964.088562000000 -836.437561000000 -2959.693600000000 0.000000000000 5705.317380000000 -964.088562000000 3221.904050000000 19 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6265.050290000000 -1085.179810000000 0.000000000000 5000.000000000000 0.000000000000 -6265.050290000000 0.000000000000 310.536957000000 0.000000000000 0.000000000000 5000.000000000000 1085.179810000000 -310.536957000000 0.000000000000 0.000000000000 -6265.050290000000 1085.179810000000 8574.719730000001 164.938538000000 -739.458862000000 6265.050290000000 0.000000000000 -310.536957000000 164.938538000000 9229.418949999999 -1158.622440000000 -1085.179810000000 310.536957000000 0.000000000000 -739.458862000000 -1158.622440000000 1351.650630000000 19 45 60 2897.000000000000 0.000000000000 0.000000000000 0.000000000000 6808.787600000000 1289.521240000000 0.000000000000 2897.000000000000 0.000000000000 -6808.787600000000 0.000000000000 -3324.657470000000 0.000000000000 0.000000000000 2897.000000000000 -1289.521240000000 3324.657470000000 0.000000000000 0.000000000000 -6808.787600000000 -1289.521240000000 16912.384800000000 -1461.571780000000 7807.461910000000 6808.787600000000 0.000000000000 3324.657470000000 -1461.571780000000 20030.636699999999 3153.134030000000 1289.521240000000 -3324.657470000000 0.000000000000 7807.461910000000 3153.134030000000 4761.842770000000 19 46 60 3283.000000000000 0.000000000000 0.000000000000 0.000000000000 7871.504880000000 1643.617800000000 0.000000000000 3283.000000000000 0.000000000000 -7871.504880000000 0.000000000000 -2852.045650000000 0.000000000000 0.000000000000 3283.000000000000 -1643.617800000000 2852.045650000000 0.000000000000 0.000000000000 -7871.504880000000 -1643.617800000000 20050.382799999999 -1299.206540000000 6734.154790000000 7871.504880000000 0.000000000000 2852.045650000000 -1299.206540000000 21804.503900000000 4077.334230000000 1643.617800000000 -2852.045650000000 0.000000000000 6734.154790000000 4077.334230000000 3896.246090000000 19 47 60 3606.000000000000 0.000000000000 0.000000000000 0.000000000000 9071.456050000001 2202.376460000000 0.000000000000 3606.000000000000 0.000000000000 -9071.456050000001 0.000000000000 -2075.822750000000 0.000000000000 0.000000000000 3606.000000000000 -2202.376460000000 2075.822750000000 0.000000000000 0.000000000000 -9071.456050000001 -2202.376460000000 24492.769499999999 -1253.741090000000 5039.041500000000 9071.456050000001 0.000000000000 2075.822750000000 -1253.741090000000 24880.933600000000 5627.419430000000 2202.376460000000 -2075.822750000000 0.000000000000 5039.041500000000 5627.419430000000 3441.243650000000 19 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13454.945299999999 2538.396480000000 0.000000000000 5000.000000000000 0.000000000000 -13454.945299999999 0.000000000000 -751.414063000000 0.000000000000 0.000000000000 5000.000000000000 -2538.396480000000 751.414063000000 0.000000000000 0.000000000000 -13454.945299999999 -2538.396480000000 38256.000000000000 -760.030701000000 1178.631960000000 13454.945299999999 0.000000000000 751.414063000000 -760.030701000000 39064.730499999998 6713.366700000000 2538.396480000000 -751.414063000000 0.000000000000 1178.631960000000 6713.366700000000 3990.075440000000 19 50 60 2627.000000000000 0.000000000000 0.000000000000 0.000000000000 6864.083500000000 1545.406740000000 0.000000000000 2627.000000000000 0.000000000000 -6864.083500000000 0.000000000000 -1047.104370000000 0.000000000000 0.000000000000 2627.000000000000 -1545.406740000000 1047.104370000000 0.000000000000 0.000000000000 -6864.083500000000 -1545.406740000000 19017.617200000001 -606.581238000000 2575.640630000000 6864.083500000000 0.000000000000 1047.104370000000 -606.581238000000 19034.293000000001 4061.894780000000 1545.406740000000 -1047.104370000000 0.000000000000 2575.640630000000 4061.894780000000 1987.062130000000 19 51 60 1509.000000000000 0.000000000000 0.000000000000 0.000000000000 3778.175540000000 820.533508000000 0.000000000000 1509.000000000000 0.000000000000 -3778.175540000000 0.000000000000 -1123.788700000000 0.000000000000 0.000000000000 1509.000000000000 -820.533508000000 1123.788700000000 0.000000000000 0.000000000000 -3778.175540000000 -820.533508000000 9972.641600000001 -597.846375000000 2802.080320000000 3778.175540000000 0.000000000000 1123.788700000000 -597.846375000000 10459.588900000001 2076.019290000000 820.533508000000 -1123.788700000000 0.000000000000 2802.080320000000 2076.019290000000 1467.586910000000 19 52 60 3089.000000000000 0.000000000000 0.000000000000 0.000000000000 8006.432130000000 1742.324710000000 0.000000000000 3089.000000000000 0.000000000000 -8006.432130000000 0.000000000000 -1139.185300000000 0.000000000000 0.000000000000 3089.000000000000 -1742.324710000000 1139.185300000000 0.000000000000 0.000000000000 -8006.432130000000 -1742.324710000000 21980.062500000000 -594.399170000000 2743.865970000000 8006.432130000000 0.000000000000 1139.185300000000 -594.399170000000 22055.511699999999 4568.197750000000 1742.324710000000 -1139.185300000000 0.000000000000 2743.865970000000 4568.197750000000 2275.770020000000 19 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10573.441400000000 466.755890000000 0.000000000000 5000.000000000000 0.000000000000 -10573.441400000000 0.000000000000 2696.038570000000 0.000000000000 0.000000000000 5000.000000000000 -466.755890000000 -2696.038570000000 0.000000000000 0.000000000000 -10573.441400000000 -466.755890000000 26468.250000000000 635.862610000000 -6666.575680000000 10573.441400000000 0.000000000000 -2696.038570000000 635.862610000000 27976.095700000002 2077.324950000000 466.755890000000 2696.038570000000 0.000000000000 -6666.575680000000 2077.324950000000 2614.486330000000 19 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7130.087890000000 -711.893860000000 0.000000000000 5000.000000000000 0.000000000000 -7130.087890000000 0.000000000000 1517.356320000000 0.000000000000 0.000000000000 5000.000000000000 711.893860000000 -1517.356320000000 0.000000000000 0.000000000000 -7130.087890000000 711.893860000000 11935.033200000000 78.681739800000 -2877.321040000000 7130.087890000000 0.000000000000 -1517.356320000000 78.681739800000 12791.071300000000 -497.230804000000 -711.893860000000 1517.356320000000 0.000000000000 -2877.321040000000 -497.230804000000 1531.689580000000 19 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6361.788570000000 -1033.922730000000 0.000000000000 5000.000000000000 0.000000000000 -6361.788570000000 0.000000000000 922.277588000000 0.000000000000 0.000000000000 5000.000000000000 1033.922730000000 -922.277588000000 0.000000000000 0.000000000000 -6361.788570000000 1033.922730000000 8759.897460000000 -96.926521300000 -1281.863890000000 6361.788570000000 0.000000000000 -922.277588000000 -96.926521300000 9154.512699999999 -1168.289060000000 -1033.922730000000 922.277588000000 0.000000000000 -1281.863890000000 -1168.289060000000 960.825989000000 19 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10014.535200000000 91.251396200000 0.000000000000 5000.000000000000 0.000000000000 -10014.535200000000 0.000000000000 1879.825810000000 0.000000000000 0.000000000000 5000.000000000000 -91.251396200000 -1879.825810000000 0.000000000000 0.000000000000 -10014.535200000000 -91.251396200000 23991.357400000001 391.030151000000 -4738.208980000000 10014.535200000000 0.000000000000 -1879.825810000000 391.030151000000 25271.412100000001 1201.515500000000 91.251396200000 1879.825810000000 0.000000000000 -4738.208980000000 1201.515500000000 2052.315670000000 20 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13301.920899999999 1259.007080000000 0.000000000000 5000.000000000000 0.000000000000 -13301.920899999999 0.000000000000 4509.630370000000 0.000000000000 0.000000000000 5000.000000000000 -1259.007080000000 -4509.630370000000 0.000000000000 0.000000000000 -13301.920899999999 -1259.007080000000 40572.898399999998 1119.285890000000 -12532.505900000000 13301.920899999999 0.000000000000 -4509.630370000000 1119.285890000000 42619.914100000002 5401.944820000000 1259.007080000000 4509.630370000000 0.000000000000 -12532.505900000000 5401.944820000000 7624.926270000000 20 23 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14415.306600000000 2414.023190000000 0.000000000000 5000.000000000000 0.000000000000 -14415.306600000000 0.000000000000 4848.094730000000 0.000000000000 0.000000000000 5000.000000000000 -2414.023190000000 -4848.094730000000 0.000000000000 0.000000000000 -14415.306600000000 -2414.023190000000 46576.003900000003 2357.422850000000 -14374.880900000000 14415.306600000000 0.000000000000 -4848.094730000000 2357.422850000000 48947.042999999998 8602.060550000000 2414.023190000000 4848.094730000000 0.000000000000 -14374.880900000000 8602.060550000000 8420.912109999999 20 24 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14415.043000000000 2966.943120000000 0.000000000000 5000.000000000000 0.000000000000 -14415.043000000000 0.000000000000 1716.135500000000 0.000000000000 0.000000000000 5000.000000000000 -2966.943120000000 -1716.135500000000 0.000000000000 0.000000000000 -14415.043000000000 -2966.943120000000 46112.804700000001 1247.579470000000 -5171.888180000000 14415.043000000000 0.000000000000 -1716.135500000000 1247.579470000000 45597.425799999997 9822.851559999999 2966.943120000000 1716.135500000000 0.000000000000 -5171.888180000000 9822.851559999999 5495.356450000000 20 27 60 3121.000000000000 0.000000000000 0.000000000000 0.000000000000 7140.085450000000 246.450287000000 0.000000000000 3121.000000000000 0.000000000000 -7140.085450000000 0.000000000000 -2417.104000000000 0.000000000000 0.000000000000 3121.000000000000 -246.450287000000 2417.104000000000 0.000000000000 0.000000000000 -7140.085450000000 -246.450287000000 17628.802700000000 -347.822021000000 5813.276370000000 7140.085450000000 0.000000000000 2417.104000000000 -347.822021000000 19426.271499999999 1018.425780000000 246.450287000000 -2417.104000000000 0.000000000000 5813.276370000000 1018.425780000000 2363.124020000000 20 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9692.809569999999 -554.682007000000 0.000000000000 5000.000000000000 0.000000000000 -9692.809569999999 0.000000000000 480.399780000000 0.000000000000 0.000000000000 5000.000000000000 554.682007000000 -480.399780000000 0.000000000000 0.000000000000 -9692.809569999999 554.682007000000 19299.962899999999 75.500976600000 -1307.060180000000 9692.809569999999 0.000000000000 -480.399780000000 75.500976600000 20503.130900000000 -901.336243000000 -554.682007000000 480.399780000000 0.000000000000 -1307.060180000000 -901.336243000000 1511.868410000000 20 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10446.602500000001 -93.121284500000 0.000000000000 5000.000000000000 0.000000000000 -10446.602500000001 0.000000000000 -2988.796630000000 0.000000000000 0.000000000000 5000.000000000000 93.121284500000 2988.796630000000 0.000000000000 0.000000000000 -10446.602500000001 93.121284500000 23655.912100000001 -346.695465000000 7012.927250000000 10446.602500000001 0.000000000000 2988.796630000000 -346.695465000000 26251.726600000002 500.250122000000 -93.121284500000 -2988.796630000000 0.000000000000 7012.927250000000 500.250122000000 3413.381590000000 20 47 60 2138.000000000000 0.000000000000 0.000000000000 0.000000000000 6413.706540000000 1915.799930000000 0.000000000000 2138.000000000000 0.000000000000 -6413.706540000000 0.000000000000 -2032.532100000000 0.000000000000 0.000000000000 2138.000000000000 -1915.799930000000 2032.532100000000 0.000000000000 0.000000000000 -6413.706540000000 -1915.799930000000 21127.486300000000 -1787.773680000000 6014.841800000000 6413.706540000000 0.000000000000 2032.532100000000 -1787.773680000000 21462.060500000000 5798.439940000000 1915.799930000000 -2032.532100000000 0.000000000000 6014.841800000000 5798.439940000000 3985.813230000000 20 48 60 2827.000000000000 0.000000000000 0.000000000000 0.000000000000 8516.088870000000 2470.117920000000 0.000000000000 2827.000000000000 0.000000000000 -8516.088870000000 0.000000000000 -2412.661870000000 0.000000000000 0.000000000000 2827.000000000000 -2470.117920000000 2412.661870000000 0.000000000000 0.000000000000 -8516.088870000000 -2470.117920000000 28024.757799999999 -2072.182860000000 7134.427730000000 8516.088870000000 0.000000000000 2412.661870000000 -2072.182860000000 28240.636699999999 7503.124020000000 2470.117920000000 -2412.661870000000 0.000000000000 7134.427730000000 7503.124020000000 4793.340820000000 20 49 60 2656.000000000000 0.000000000000 0.000000000000 0.000000000000 8035.793460000000 2363.064210000000 0.000000000000 2656.000000000000 0.000000000000 -8035.793460000000 0.000000000000 -2157.316650000000 0.000000000000 0.000000000000 2656.000000000000 -2363.064210000000 2157.316650000000 0.000000000000 0.000000000000 -8035.793460000000 -2363.064210000000 26584.669900000001 -1901.022950000000 6391.980960000000 8035.793460000000 0.000000000000 2157.316650000000 -1901.022950000000 26685.298800000000 7193.976560000000 2363.064210000000 -2157.316650000000 0.000000000000 6391.980960000000 7193.976560000000 4510.986820000000 20 50 60 2704.000000000000 0.000000000000 0.000000000000 0.000000000000 8036.987300000000 2085.215090000000 0.000000000000 2704.000000000000 0.000000000000 -8036.987300000000 0.000000000000 -2553.210690000000 0.000000000000 0.000000000000 2704.000000000000 -2085.215090000000 2553.210690000000 0.000000000000 0.000000000000 -8036.987300000000 -2085.215090000000 25777.271499999999 -1979.335820000000 7509.662600000000 8036.987300000000 0.000000000000 2553.210690000000 -1979.335820000000 26633.912100000001 6260.314940000000 2085.215090000000 -2553.210690000000 0.000000000000 7509.662600000000 6260.314940000000 4505.749020000000 20 52 60 3362.000000000000 0.000000000000 0.000000000000 0.000000000000 10009.317400000000 2511.638430000000 0.000000000000 3362.000000000000 0.000000000000 -10009.317400000000 0.000000000000 -3044.906980000000 0.000000000000 0.000000000000 3362.000000000000 -2511.638430000000 3044.906980000000 0.000000000000 0.000000000000 -10009.317400000000 -2511.638430000000 32049.150399999999 -2245.697270000000 8929.975590000000 10009.317400000000 0.000000000000 3044.906980000000 -2245.697270000000 33103.960899999998 7565.066890000000 2511.638430000000 -3044.906980000000 0.000000000000 8929.975590000000 7565.066890000000 5378.500980000000 20 53 60 4839.000000000000 0.000000000000 0.000000000000 0.000000000000 14552.433600000000 3719.134520000000 0.000000000000 4839.000000000000 0.000000000000 -14552.433600000000 0.000000000000 -3142.759520000000 0.000000000000 0.000000000000 4839.000000000000 -3719.134520000000 3142.759520000000 0.000000000000 0.000000000000 -14552.433600000000 -3719.134520000000 47362.250000000000 -2478.728760000000 9274.479490000000 14552.433600000000 0.000000000000 3142.759520000000 -2478.728760000000 47422.601600000002 11385.780300000000 3719.134520000000 -3142.759520000000 0.000000000000 9274.479490000000 11385.780300000000 6802.027830000000 20 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10924.487300000001 235.792770000000 0.000000000000 5000.000000000000 0.000000000000 -10924.487300000001 0.000000000000 519.143188000000 0.000000000000 0.000000000000 5000.000000000000 -235.792770000000 -519.143188000000 0.000000000000 0.000000000000 -10924.487300000001 -235.792770000000 25868.460899999998 537.984802000000 -1981.702150000000 10924.487300000001 0.000000000000 -519.143188000000 537.984802000000 26829.043000000001 1390.144900000000 235.792770000000 519.143188000000 0.000000000000 -1981.702150000000 1390.144900000000 2141.220460000000 20 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10147.007799999999 -283.042877000000 0.000000000000 5000.000000000000 0.000000000000 -10147.007799999999 0.000000000000 62.569667800000 0.000000000000 0.000000000000 5000.000000000000 283.042877000000 -62.569667800000 0.000000000000 0.000000000000 -10147.007799999999 283.042877000000 21559.927700000000 275.593994000000 -786.434265000000 10147.007799999999 0.000000000000 -62.569667800000 275.593994000000 22792.791000000001 -200.716705000000 -283.042877000000 62.569667800000 0.000000000000 -786.434265000000 -200.716705000000 1656.831540000000 20 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10156.430700000001 -361.879028000000 0.000000000000 5000.000000000000 0.000000000000 -10156.430700000001 0.000000000000 -150.967117000000 0.000000000000 0.000000000000 5000.000000000000 361.879028000000 150.967117000000 0.000000000000 0.000000000000 -10156.430700000001 361.879028000000 21777.607400000001 280.538300000000 -422.278778000000 10156.430700000001 0.000000000000 150.967117000000 280.538300000000 23270.687500000000 -358.516632000000 -361.879028000000 -150.967117000000 0.000000000000 -422.278778000000 -358.516632000000 1872.727050000000 20 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9923.417970000000 -421.803833000000 0.000000000000 5000.000000000000 0.000000000000 -9923.417970000000 0.000000000000 -825.200134000000 0.000000000000 0.000000000000 5000.000000000000 421.803833000000 825.200134000000 0.000000000000 0.000000000000 -9923.417970000000 421.803833000000 20421.875000000000 1.115862730000 1722.102290000000 9923.417970000000 0.000000000000 825.200134000000 1.115862730000 21513.927700000000 -602.849609000000 -421.803833000000 -825.200134000000 0.000000000000 1722.102290000000 -602.849609000000 1414.449580000000 20 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11926.839800000000 637.838806000000 0.000000000000 5000.000000000000 0.000000000000 -11926.839800000000 0.000000000000 -2342.720700000000 0.000000000000 0.000000000000 5000.000000000000 -637.838806000000 2342.720700000000 0.000000000000 0.000000000000 -11926.839800000000 -637.838806000000 29825.830099999999 -552.846924000000 5975.665530000000 11926.839800000000 0.000000000000 2342.720700000000 -552.846924000000 33022.054700000001 1971.958860000000 637.838806000000 -2342.720700000000 0.000000000000 5975.665530000000 1971.958860000000 3915.867190000000 21 25 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13875.327100000000 3099.659670000000 0.000000000000 5000.000000000000 0.000000000000 -13875.327100000000 0.000000000000 -4203.135250000000 0.000000000000 0.000000000000 5000.000000000000 -3099.659670000000 4203.135250000000 0.000000000000 0.000000000000 -13875.327100000000 -3099.659670000000 42624.847699999998 -2690.761230000000 12117.500000000000 13875.327100000000 0.000000000000 4203.135250000000 -2690.761230000000 44048.652300000002 9307.464840000001 3099.659670000000 -4203.135250000000 0.000000000000 12117.500000000000 9307.464840000001 7204.579100000000 21 26 60 4847.000000000000 0.000000000000 0.000000000000 0.000000000000 12263.711900000000 1593.866090000000 0.000000000000 4847.000000000000 0.000000000000 -12263.711900000000 0.000000000000 -4643.368650000000 0.000000000000 0.000000000000 4847.000000000000 -1593.866090000000 4643.368650000000 0.000000000000 0.000000000000 -12263.711900000000 -1593.866090000000 34450.691400000003 -1878.715700000000 12623.868200000001 12263.711900000000 0.000000000000 4643.368650000000 -1878.715700000000 38086.777300000002 4940.770510000000 1593.866090000000 -4643.368650000000 0.000000000000 12623.868200000001 4940.770510000000 6362.458500000000 21 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9407.451170000000 -152.500320000000 0.000000000000 5000.000000000000 0.000000000000 -9407.451170000000 0.000000000000 -531.290833000000 0.000000000000 0.000000000000 5000.000000000000 152.500320000000 531.290833000000 0.000000000000 0.000000000000 -9407.451170000000 152.500320000000 18210.451200000000 16.441289900000 883.944580000000 9407.451170000000 0.000000000000 531.290833000000 16.441289900000 18770.232400000001 -71.836395300000 -152.500320000000 -531.290833000000 0.000000000000 883.944580000000 -71.836395300000 846.591125000000 21 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14754.632799999999 3431.375730000000 0.000000000000 5000.000000000000 0.000000000000 -14754.632799999999 0.000000000000 -3060.506590000000 0.000000000000 0.000000000000 5000.000000000000 -3431.375730000000 3060.506590000000 0.000000000000 0.000000000000 -14754.632799999999 -3431.375730000000 47640.257799999999 -2168.033450000000 8552.020510000000 14754.632799999999 0.000000000000 3060.506590000000 -2168.033450000000 48357.398399999998 10544.186500000000 3431.375730000000 -3060.506590000000 0.000000000000 8552.020510000000 10544.186500000000 6819.136230000000 21 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14307.346700000000 2580.158940000000 0.000000000000 5000.000000000000 0.000000000000 -14307.346700000000 0.000000000000 -4732.802250000000 0.000000000000 0.000000000000 5000.000000000000 -2580.158940000000 4732.802250000000 0.000000000000 0.000000000000 -14307.346700000000 -2580.158940000000 44298.152300000002 -2602.875980000000 13864.709000000001 14307.346700000000 0.000000000000 4732.802250000000 -2602.875980000000 47391.386700000003 7977.300290000000 2580.158940000000 -4732.802250000000 0.000000000000 13864.709000000001 7977.300290000000 6842.105960000000 21 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12659.687500000000 1169.542970000000 0.000000000000 5000.000000000000 0.000000000000 -12659.687500000000 0.000000000000 -3775.460450000000 0.000000000000 0.000000000000 5000.000000000000 -1169.542970000000 3775.460450000000 0.000000000000 0.000000000000 -12659.687500000000 -1169.542970000000 36198.945299999999 -1246.144530000000 10566.036099999999 12659.687500000000 0.000000000000 3775.460450000000 -1246.144530000000 38770.910199999998 4272.085450000000 1169.542970000000 -3775.460450000000 0.000000000000 10566.036099999999 4272.085450000000 4384.879390000000 21 49 60 2645.000000000000 0.000000000000 0.000000000000 0.000000000000 7857.349610000000 2486.751710000000 0.000000000000 2645.000000000000 0.000000000000 -7857.349610000000 0.000000000000 -2738.187260000000 0.000000000000 0.000000000000 2645.000000000000 -2486.751710000000 2738.187260000000 0.000000000000 0.000000000000 -7857.349610000000 -2486.751710000000 25846.056600000000 -2544.366940000000 8094.790040000000 7857.349610000000 0.000000000000 2738.187260000000 -2544.366940000000 26393.378900000000 7356.282230000000 2486.751710000000 -2738.187260000000 0.000000000000 8094.790040000000 7356.282230000000 5406.245610000000 21 52 60 2471.000000000000 0.000000000000 0.000000000000 0.000000000000 7434.467290000000 2073.710690000000 0.000000000000 2471.000000000000 0.000000000000 -7434.467290000000 0.000000000000 -2673.675780000000 0.000000000000 0.000000000000 2471.000000000000 -2073.710690000000 2673.675780000000 0.000000000000 0.000000000000 -7434.467290000000 -2073.710690000000 24344.650399999999 -2257.143800000000 7985.425780000000 7434.467290000000 0.000000000000 2673.675780000000 -2257.143800000000 25490.568400000000 6180.155270000000 2073.710690000000 -2673.675780000000 0.000000000000 7985.425780000000 6180.155270000000 4859.035160000000 21 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14910.736300000000 4512.149410000000 0.000000000000 5000.000000000000 0.000000000000 -14910.736300000000 0.000000000000 -4599.781250000000 0.000000000000 0.000000000000 5000.000000000000 -4512.149410000000 4599.781250000000 0.000000000000 0.000000000000 -14910.736300000000 -4512.149410000000 49045.851600000002 -4096.159670000000 13623.051799999999 14910.736300000000 0.000000000000 4599.781250000000 -4096.159670000000 49336.312500000000 13449.002899999999 4512.149410000000 -4599.781250000000 0.000000000000 13623.051799999999 13449.002899999999 8994.349609999999 21 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10768.127899999999 513.795349000000 0.000000000000 5000.000000000000 0.000000000000 -10768.127899999999 0.000000000000 587.754211000000 0.000000000000 0.000000000000 5000.000000000000 -513.795349000000 -587.754211000000 0.000000000000 0.000000000000 -10768.127899999999 -513.795349000000 25487.328099999999 551.527893000000 -2444.094240000000 10768.127899999999 0.000000000000 -587.754211000000 551.527893000000 26984.168000000001 1982.524290000000 513.795349000000 587.754211000000 0.000000000000 -2444.094240000000 1982.524290000000 2599.351810000000 21 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10578.941400000000 272.528564000000 0.000000000000 5000.000000000000 0.000000000000 -10578.941400000000 0.000000000000 -194.192368000000 0.000000000000 0.000000000000 5000.000000000000 -272.528564000000 194.192368000000 0.000000000000 0.000000000000 -10578.941400000000 -272.528564000000 25080.841799999998 539.397156000000 -879.827637000000 10578.941400000000 0.000000000000 194.192368000000 539.397156000000 26439.503900000000 1555.241090000000 272.528564000000 -194.192368000000 0.000000000000 -879.827637000000 1555.241090000000 2300.197510000000 21 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11241.069299999999 730.620056000000 0.000000000000 5000.000000000000 0.000000000000 -11241.069299999999 0.000000000000 -1696.209960000000 0.000000000000 0.000000000000 5000.000000000000 -730.620056000000 1696.209960000000 0.000000000000 0.000000000000 -11241.069299999999 -730.620056000000 28167.160199999998 -535.059509000000 4241.407710000000 11241.069299999999 0.000000000000 1696.209960000000 -535.059509000000 30001.816400000000 2718.059330000000 730.620056000000 -1696.209960000000 0.000000000000 4241.407710000000 2718.059330000000 3223.991210000000 21 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14082.299800000001 2081.906740000000 0.000000000000 5000.000000000000 0.000000000000 -14082.299800000001 0.000000000000 -2203.345950000000 0.000000000000 0.000000000000 5000.000000000000 -2081.906740000000 2203.345950000000 0.000000000000 0.000000000000 -14082.299800000001 -2081.906740000000 42974.144500000002 -927.961914000000 6220.562500000000 14082.299800000001 0.000000000000 2203.345950000000 -927.961914000000 45197.277300000002 6746.679200000000 2081.906740000000 -2203.345950000000 0.000000000000 6220.562500000000 6746.679200000000 4932.120610000000 22 25 60 3614.000000000000 0.000000000000 0.000000000000 0.000000000000 9135.231449999999 1647.164180000000 0.000000000000 3614.000000000000 0.000000000000 -9135.231449999999 0.000000000000 -3805.614010000000 0.000000000000 0.000000000000 3614.000000000000 -1647.164180000000 3805.614010000000 0.000000000000 0.000000000000 -9135.231449999999 -1647.164180000000 25690.044900000001 -2116.148930000000 10061.206099999999 9135.231449999999 0.000000000000 3805.614010000000 -2116.148930000000 28545.988300000001 4632.446780000000 1647.164180000000 -3805.614010000000 0.000000000000 10061.206099999999 4632.446780000000 5912.141600000000 22 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15961.286099999999 1622.672490000000 0.000000000000 5000.000000000000 0.000000000000 -15961.286099999999 0.000000000000 -5247.702640000000 0.000000000000 0.000000000000 5000.000000000000 -1622.672490000000 5247.702640000000 0.000000000000 0.000000000000 -15961.286099999999 -1622.672490000000 52016.589800000002 -1601.955930000000 16624.068400000000 15961.286099999999 0.000000000000 5247.702640000000 -1601.955930000000 57275.070299999999 5176.627440000000 1622.672490000000 -5247.702640000000 0.000000000000 16624.068400000000 5176.627440000000 7014.589840000000 22 38 60 4774.000000000000 0.000000000000 0.000000000000 0.000000000000 14315.892599999999 1203.328000000000 0.000000000000 4774.000000000000 0.000000000000 -14315.892599999999 0.000000000000 -5628.221680000000 0.000000000000 0.000000000000 4774.000000000000 -1203.328000000000 5628.221680000000 0.000000000000 0.000000000000 -14315.892599999999 -1203.328000000000 44722.078099999999 -1445.857790000000 17216.064500000000 14315.892599999999 0.000000000000 5628.221680000000 -1445.857790000000 51109.277300000002 3897.972170000000 1203.328000000000 -5628.221680000000 0.000000000000 17216.064500000000 3897.972170000000 7459.625000000000 22 39 60 4122.000000000000 0.000000000000 0.000000000000 0.000000000000 10558.445299999999 1896.673830000000 0.000000000000 4122.000000000000 0.000000000000 -10558.445299999999 0.000000000000 -4325.566410000000 0.000000000000 0.000000000000 4122.000000000000 -1896.673830000000 4325.566410000000 0.000000000000 0.000000000000 -10558.445299999999 -1896.673830000000 30033.238300000001 -2250.479980000000 11603.810500000000 10558.445299999999 0.000000000000 4325.566410000000 -2250.479980000000 33496.675799999997 5700.397460000000 1896.673830000000 -4325.566410000000 0.000000000000 11603.810500000000 5700.397460000000 6417.924800000000 22 53 60 3477.000000000000 0.000000000000 0.000000000000 0.000000000000 10669.370100000000 1332.644530000000 0.000000000000 3477.000000000000 0.000000000000 -10669.370100000000 0.000000000000 -4307.176270000000 0.000000000000 0.000000000000 3477.000000000000 -1332.644530000000 4307.176270000000 0.000000000000 0.000000000000 -10669.370100000000 -1332.644530000000 33930.968800000002 -1674.118900000000 13130.092800000000 10669.370100000000 0.000000000000 4307.176270000000 -1674.118900000000 38516.226600000002 3807.948970000000 1332.644530000000 -4307.176270000000 0.000000000000 13130.092800000000 3807.948970000000 6303.632320000000 22 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13890.815399999999 1397.136720000000 0.000000000000 5000.000000000000 0.000000000000 -13890.815399999999 0.000000000000 -3037.891110000000 0.000000000000 0.000000000000 5000.000000000000 -1397.136720000000 3037.891110000000 0.000000000000 0.000000000000 -13890.815399999999 -1397.136720000000 41798.503900000003 -1057.089360000000 9554.543949999999 13890.815399999999 0.000000000000 3037.891110000000 -1057.089360000000 44265.992200000001 4590.761230000000 1397.136720000000 -3037.891110000000 0.000000000000 9554.543949999999 4590.761230000000 4317.788570000000 22 57 60 4404.000000000000 0.000000000000 0.000000000000 0.000000000000 11016.289100000000 618.983276000000 0.000000000000 4404.000000000000 0.000000000000 -11016.289100000000 0.000000000000 -1341.565550000000 0.000000000000 0.000000000000 4404.000000000000 -618.983276000000 1341.565550000000 0.000000000000 0.000000000000 -11016.289100000000 -618.983276000000 30861.599600000001 -122.096863000000 3537.015140000000 11016.289100000000 0.000000000000 1341.565550000000 -122.096863000000 31194.923800000000 2437.991700000000 618.983276000000 -1341.565550000000 0.000000000000 3537.015140000000 2437.991700000000 1477.226070000000 22 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13438.110400000000 826.464417000000 0.000000000000 5000.000000000000 0.000000000000 -13438.110400000000 0.000000000000 -3988.043950000000 0.000000000000 0.000000000000 5000.000000000000 -826.464417000000 3988.043950000000 0.000000000000 0.000000000000 -13438.110400000000 -826.464417000000 39605.886700000003 -950.091919000000 11989.929700000001 13438.110400000000 0.000000000000 3988.043950000000 -950.091919000000 43573.042999999998 3041.293950000000 826.464417000000 -3988.043950000000 0.000000000000 11989.929700000001 3041.293950000000 5120.060060000000 22 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14860.553700000000 1511.566040000000 0.000000000000 5000.000000000000 0.000000000000 -14860.553700000000 0.000000000000 -3750.596680000000 0.000000000000 0.000000000000 5000.000000000000 -1511.566040000000 3750.596680000000 0.000000000000 0.000000000000 -14860.553700000000 -1511.566040000000 46237.566400000003 -1059.365600000000 11574.393599999999 14860.553700000000 0.000000000000 3750.596680000000 -1059.365600000000 49535.058599999997 4731.666990000000 1511.566040000000 -3750.596680000000 0.000000000000 11574.393599999999 4731.666990000000 4886.412600000000 23 25 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12570.742200000001 167.502609000000 0.000000000000 5000.000000000000 0.000000000000 -12570.742200000001 0.000000000000 -5423.939940000000 0.000000000000 0.000000000000 5000.000000000000 -167.502609000000 5423.939940000000 0.000000000000 0.000000000000 -12570.742200000001 -167.502609000000 33919.957000000002 -573.452759000000 13789.432600000000 12570.742200000001 0.000000000000 5423.939940000000 -573.452759000000 38917.015599999999 499.575745000000 167.502609000000 -5423.939940000000 0.000000000000 13789.432600000000 499.575745000000 7324.034670000000 23 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14605.210900000000 214.402039000000 0.000000000000 5000.000000000000 0.000000000000 -14605.210900000000 0.000000000000 -5333.858890000000 0.000000000000 0.000000000000 5000.000000000000 -214.402039000000 5333.858890000000 0.000000000000 0.000000000000 -14605.210900000000 -214.402039000000 43455.335899999998 -146.682343000000 15510.898400000000 14605.210900000000 0.000000000000 5333.858890000000 -146.682343000000 49212.421900000001 752.159546000000 214.402039000000 -5333.858890000000 0.000000000000 15510.898400000000 752.159546000000 6794.022460000000 23 38 60 3931.000000000000 0.000000000000 0.000000000000 0.000000000000 11015.775400000000 289.238190000000 0.000000000000 3931.000000000000 0.000000000000 -11015.775400000000 0.000000000000 -4591.667970000000 0.000000000000 0.000000000000 3931.000000000000 -289.238190000000 4591.667970000000 0.000000000000 0.000000000000 -11015.775400000000 -289.238190000000 32283.474600000001 -325.424866000000 12959.379900000000 11015.775400000000 0.000000000000 4591.667970000000 -325.424866000000 37552.406300000002 1096.999270000000 289.238190000000 -4591.667970000000 0.000000000000 12959.379900000000 1096.999270000000 5761.381840000000 23 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12963.907200000000 1782.838870000000 0.000000000000 5000.000000000000 0.000000000000 -12963.907200000000 0.000000000000 -5870.357420000000 0.000000000000 0.000000000000 5000.000000000000 -1782.838870000000 5870.357420000000 0.000000000000 0.000000000000 -12963.907200000000 -1782.838870000000 35845.906300000002 -2136.882570000000 15409.149400000000 12963.907200000000 0.000000000000 5870.357420000000 -2136.882570000000 41913.886700000003 5126.210940000000 1782.838870000000 -5870.357420000000 0.000000000000 15409.149400000000 5126.210940000000 8256.759770000001 23 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14582.605500000000 540.609070000000 0.000000000000 5000.000000000000 0.000000000000 -14582.605500000000 0.000000000000 -6028.545410000000 0.000000000000 0.000000000000 5000.000000000000 -540.609070000000 6028.545410000000 0.000000000000 0.000000000000 -14582.605500000000 -540.609070000000 43394.910199999998 -717.393982000000 17502.599600000001 14582.605500000000 0.000000000000 6028.545410000000 -717.393982000000 50171.441400000003 1443.140750000000 540.609070000000 -6028.545410000000 0.000000000000 17502.599600000001 1443.140750000000 8017.315920000000 23 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11991.147499999999 -258.570404000000 0.000000000000 5000.000000000000 0.000000000000 -11991.147499999999 0.000000000000 -3200.529050000000 0.000000000000 0.000000000000 5000.000000000000 258.570404000000 3200.529050000000 0.000000000000 0.000000000000 -11991.147499999999 258.570404000000 31444.105500000001 272.022125000000 8739.234380000000 11991.147499999999 0.000000000000 3200.529050000000 272.022125000000 34670.542999999998 -266.024292000000 -258.570404000000 -3200.529050000000 0.000000000000 8739.234380000000 -266.024292000000 4208.935550000000 23 57 60 3937.000000000000 0.000000000000 0.000000000000 0.000000000000 9586.424800000001 -569.527832000000 0.000000000000 3937.000000000000 0.000000000000 -9586.424800000001 0.000000000000 -2604.820560000000 0.000000000000 0.000000000000 3937.000000000000 569.527832000000 2604.820560000000 0.000000000000 0.000000000000 -9586.424800000001 569.527832000000 25746.714800000002 616.951843000000 6791.538570000000 9586.424800000001 0.000000000000 2604.820560000000 616.951843000000 27972.498000000000 -1042.652100000000 -569.527832000000 -2604.820560000000 0.000000000000 6791.538570000000 -1042.652100000000 3023.849850000000 23 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12743.318400000000 249.877350000000 0.000000000000 5000.000000000000 0.000000000000 -12743.318400000000 0.000000000000 -4641.549320000000 0.000000000000 0.000000000000 5000.000000000000 -249.877350000000 4641.549320000000 0.000000000000 0.000000000000 -12743.318400000000 -249.877350000000 35165.414100000002 -448.939117000000 12730.017599999999 12743.318400000000 0.000000000000 4641.549320000000 -448.939117000000 40115.300799999997 1293.516850000000 249.877350000000 -4641.549320000000 0.000000000000 12730.017599999999 1293.516850000000 5838.719730000000 23 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14438.202100000000 828.172363000000 0.000000000000 5000.000000000000 0.000000000000 -14438.202100000000 0.000000000000 -4662.228520000000 0.000000000000 0.000000000000 5000.000000000000 -828.172363000000 4662.228520000000 0.000000000000 0.000000000000 -14438.202100000000 -828.172363000000 42955.488299999997 -711.009827000000 13764.881799999999 14438.202100000000 0.000000000000 4662.228520000000 -711.009827000000 47729.328099999999 2552.762700000000 828.172363000000 -4662.228520000000 0.000000000000 13764.881799999999 2552.762700000000 5696.920410000000 24 38 60 3681.000000000000 0.000000000000 0.000000000000 0.000000000000 8869.755859999999 -382.993256000000 0.000000000000 3681.000000000000 0.000000000000 -8869.755859999999 0.000000000000 -2768.344970000000 0.000000000000 0.000000000000 3681.000000000000 382.993256000000 2768.344970000000 0.000000000000 0.000000000000 -8869.755859999999 382.993256000000 22873.976600000002 333.325348000000 6521.693360000000 8869.755859999999 0.000000000000 2768.344970000000 333.325348000000 25400.203099999999 -755.587769000000 -382.993256000000 -2768.344970000000 0.000000000000 6521.693360000000 -755.587769000000 3093.144530000000 24 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12450.820299999999 1277.295410000000 0.000000000000 5000.000000000000 0.000000000000 -12450.820299999999 0.000000000000 -3094.659420000000 0.000000000000 0.000000000000 5000.000000000000 -1277.295410000000 3094.659420000000 0.000000000000 0.000000000000 -12450.820299999999 -1277.295410000000 32825.871099999997 -676.786438000000 7650.208980000000 12450.820299999999 0.000000000000 3094.659420000000 -676.786438000000 34972.988299999997 3418.519040000000 1277.295410000000 -3094.659420000000 0.000000000000 7650.208980000000 3418.519040000000 3930.722170000000 24 48 60 3446.000000000000 0.000000000000 0.000000000000 0.000000000000 9297.357420000000 1604.522220000000 0.000000000000 3446.000000000000 0.000000000000 -9297.357420000000 0.000000000000 -2699.314940000000 0.000000000000 0.000000000000 3446.000000000000 -1604.522220000000 2699.314940000000 0.000000000000 0.000000000000 -9297.357420000000 -1604.522220000000 26324.793000000001 -1517.380370000000 7145.641110000000 9297.357420000000 0.000000000000 2699.314940000000 -1517.380370000000 27640.986300000000 4136.785640000000 1604.522220000000 -2699.314940000000 0.000000000000 7145.641110000000 4136.785640000000 3569.649170000000 24 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13532.027300000000 1856.547120000000 0.000000000000 5000.000000000000 0.000000000000 -13532.027300000000 0.000000000000 -3027.072020000000 0.000000000000 0.000000000000 5000.000000000000 -1856.547120000000 3027.072020000000 0.000000000000 0.000000000000 -13532.027300000000 -1856.547120000000 38146.210899999998 -1648.185180000000 7917.661130000000 13532.027300000000 0.000000000000 3027.072020000000 -1648.185180000000 39407.062500000000 4703.871580000000 1856.547120000000 -3027.072020000000 0.000000000000 7917.661130000000 4703.871580000000 3893.656250000000 24 52 60 3352.000000000000 0.000000000000 0.000000000000 0.000000000000 8854.080080000000 1055.682980000000 0.000000000000 3352.000000000000 0.000000000000 -8854.080080000000 0.000000000000 -3155.057620000000 0.000000000000 0.000000000000 3352.000000000000 -1055.682980000000 3155.057620000000 0.000000000000 0.000000000000 -8854.080080000000 -1055.682980000000 24690.966799999998 -1290.723750000000 8229.389649999999 8854.080080000000 0.000000000000 3155.057620000000 -1290.723750000000 26733.855500000001 2539.529300000000 1055.682980000000 -3155.057620000000 0.000000000000 8229.389649999999 2539.529300000000 4398.720210000000 24 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10555.550800000001 -1708.044800000000 0.000000000000 5000.000000000000 0.000000000000 -10555.550800000001 0.000000000000 -2751.764890000000 0.000000000000 0.000000000000 5000.000000000000 1708.044800000000 2751.764890000000 0.000000000000 0.000000000000 -10555.550800000001 1708.044800000000 24885.710899999998 1035.735470000000 6077.725590000000 10555.550800000001 0.000000000000 2751.764890000000 1035.735470000000 27076.798800000000 -3675.941410000000 -1708.044800000000 -2751.764890000000 0.000000000000 6077.725590000000 -3675.941410000000 3889.057860000000 24 57 60 4621.000000000000 0.000000000000 0.000000000000 0.000000000000 10392.373000000000 -1761.545530000000 0.000000000000 4621.000000000000 0.000000000000 -10392.373000000000 0.000000000000 -3377.450440000000 0.000000000000 0.000000000000 4621.000000000000 1761.545530000000 3377.450440000000 0.000000000000 0.000000000000 -10392.373000000000 1761.545530000000 25609.208999999999 1239.969120000000 7785.536620000000 10392.373000000000 0.000000000000 3377.450440000000 1239.969120000000 28479.285199999998 -4049.876460000000 -1761.545530000000 -3377.450440000000 0.000000000000 7785.536620000000 -4049.876460000000 4386.796390000000 25 27 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14860.261699999999 330.425018000000 0.000000000000 5000.000000000000 0.000000000000 -14860.261699999999 0.000000000000 -5574.362300000000 0.000000000000 0.000000000000 5000.000000000000 -330.425018000000 5574.362300000000 0.000000000000 0.000000000000 -14860.261699999999 -330.425018000000 45521.308599999997 -470.771515000000 16726.250000000000 14860.261699999999 0.000000000000 5574.362300000000 -470.771515000000 51087.027300000002 1123.490110000000 330.425018000000 -5574.362300000000 0.000000000000 16726.250000000000 1123.490110000000 7391.706050000000 25 34 60 2507.000000000000 0.000000000000 0.000000000000 0.000000000000 5017.425290000000 -708.156189000000 0.000000000000 2507.000000000000 0.000000000000 -5017.425290000000 0.000000000000 -1494.806640000000 0.000000000000 0.000000000000 2507.000000000000 708.156189000000 1494.806640000000 0.000000000000 0.000000000000 -5017.425290000000 708.156189000000 11033.253900000000 429.684998000000 2981.073000000000 5017.425290000000 0.000000000000 1494.806640000000 429.684998000000 11748.515600000001 -1476.938480000000 -708.156189000000 -1494.806640000000 0.000000000000 2981.073000000000 -1476.938480000000 1420.141970000000 25 46 60 4048.000000000000 0.000000000000 0.000000000000 0.000000000000 11574.158200000000 4247.142580000000 0.000000000000 4048.000000000000 0.000000000000 -11574.158200000000 0.000000000000 -3422.289790000000 0.000000000000 0.000000000000 4048.000000000000 -4247.142580000000 3422.289790000000 0.000000000000 0.000000000000 -11574.158200000000 -4247.142580000000 37974.007799999999 -3553.309570000000 10057.003900000000 11574.158200000000 0.000000000000 3422.289790000000 -3553.309570000000 36690.921900000001 12209.790000000001 4247.142580000000 -3422.289790000000 0.000000000000 10057.003900000000 12209.790000000001 8061.003910000000 25 47 60 4012.000000000000 0.000000000000 0.000000000000 0.000000000000 10981.323200000001 4044.448490000000 0.000000000000 4012.000000000000 0.000000000000 -10981.323200000001 0.000000000000 -2745.643550000000 0.000000000000 0.000000000000 4012.000000000000 -4044.448490000000 2745.643550000000 0.000000000000 0.000000000000 -10981.323200000001 -4044.448490000000 34561.070299999999 -2828.400150000000 7816.856450000000 10981.323200000001 0.000000000000 2745.643550000000 -2828.400150000000 32704.808600000000 11179.040999999999 4044.448490000000 -2745.643550000000 0.000000000000 7816.856450000000 11179.040999999999 6690.215820000000 25 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12950.781300000001 4343.372070000000 0.000000000000 5000.000000000000 0.000000000000 -12950.781300000001 0.000000000000 -1757.826780000000 0.000000000000 0.000000000000 5000.000000000000 -4343.372070000000 1757.826780000000 0.000000000000 0.000000000000 -12950.781300000001 -4343.372070000000 38152.484400000001 -2053.406740000000 5129.210940000000 12950.781300000001 0.000000000000 1757.826780000000 -2053.406740000000 35864.109400000001 11463.462900000000 4343.372070000000 -1757.826780000000 0.000000000000 5129.210940000000 11463.462900000000 6245.269530000000 25 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12354.923800000000 3776.378660000000 0.000000000000 5000.000000000000 0.000000000000 -12354.923800000000 0.000000000000 -590.179138000000 0.000000000000 0.000000000000 5000.000000000000 -3776.378660000000 590.179138000000 0.000000000000 0.000000000000 -12354.923800000000 -3776.378660000000 34549.855499999998 -1327.532590000000 2141.507810000000 12354.923800000000 0.000000000000 590.179138000000 -1327.532590000000 32652.831999999999 9624.417970000000 3776.378660000000 -590.179138000000 0.000000000000 2141.507810000000 9624.417970000000 5347.574220000000 25 50 60 4075.000000000000 0.000000000000 0.000000000000 0.000000000000 10859.708000000001 3886.029300000000 0.000000000000 4075.000000000000 0.000000000000 -10859.708000000001 0.000000000000 -2062.301510000000 0.000000000000 0.000000000000 4075.000000000000 -3886.029300000000 2062.301510000000 0.000000000000 0.000000000000 -10859.708000000001 -3886.029300000000 33123.226600000002 -2131.681640000000 5812.403320000000 10859.708000000001 0.000000000000 2062.301510000000 -2131.681640000000 30802.671900000001 10449.711900000000 3886.029300000000 -2062.301510000000 0.000000000000 5812.403320000000 10449.711900000000 5602.935060000000 25 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12973.028300000000 3492.083500000000 0.000000000000 5000.000000000000 0.000000000000 -12973.028300000000 0.000000000000 -1434.271000000000 0.000000000000 0.000000000000 5000.000000000000 -3492.083500000000 1434.271000000000 0.000000000000 0.000000000000 -12973.028300000000 -3492.083500000000 37762.179700000001 -1944.413090000000 4179.159670000000 12973.028300000000 0.000000000000 1434.271000000000 -1944.413090000000 35565.300799999997 9283.551760000000 3492.083500000000 -1434.271000000000 0.000000000000 4179.159670000000 9283.551760000000 5391.992190000000 25 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11108.508800000000 -1664.113650000000 0.000000000000 5000.000000000000 0.000000000000 -11108.508800000000 0.000000000000 -1470.999150000000 0.000000000000 0.000000000000 5000.000000000000 1664.113650000000 1470.999150000000 0.000000000000 0.000000000000 -11108.508800000000 1664.113650000000 26266.160199999998 253.120651000000 3080.980710000000 11108.508800000000 0.000000000000 1470.999150000000 253.120651000000 27128.892599999999 -3791.986080000000 -1664.113650000000 -1470.999150000000 0.000000000000 3080.980710000000 -3791.986080000000 2434.505130000000 25 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11326.940399999999 -1727.564820000000 0.000000000000 5000.000000000000 0.000000000000 -11326.940399999999 0.000000000000 -1933.577640000000 0.000000000000 0.000000000000 5000.000000000000 1727.564820000000 1933.577640000000 0.000000000000 0.000000000000 -11326.940399999999 1727.564820000000 27258.437500000000 335.601990000000 4342.375490000000 11326.940399999999 0.000000000000 1933.577640000000 335.601990000000 28436.304700000001 -3958.789790000000 -1727.564820000000 -1933.577640000000 0.000000000000 4342.375490000000 -3958.789790000000 2749.428470000000 26 28 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16037.719700000000 1113.815430000000 0.000000000000 5000.000000000000 0.000000000000 -16037.719700000000 0.000000000000 -4634.812990000000 0.000000000000 0.000000000000 5000.000000000000 -1113.815430000000 4634.812990000000 0.000000000000 0.000000000000 -16037.719700000000 -1113.815430000000 53418.113299999997 -1147.729130000000 14840.391600000001 16037.719700000000 0.000000000000 4634.812990000000 -1147.729130000000 56825.890599999999 3865.439450000000 1113.815430000000 -4634.812990000000 0.000000000000 14840.391600000001 3865.439450000000 6040.007320000000 26 29 60 3571.000000000000 0.000000000000 0.000000000000 0.000000000000 12238.325199999999 2102.530270000000 0.000000000000 3571.000000000000 0.000000000000 -12238.325199999999 0.000000000000 -4124.521000000000 0.000000000000 0.000000000000 3571.000000000000 -2102.530270000000 4124.521000000000 0.000000000000 0.000000000000 -12238.325199999999 -2102.530270000000 43766.187500000000 -2257.244630000000 14127.727500000001 12238.325199999999 0.000000000000 4124.521000000000 -2257.244630000000 46886.070299999999 7218.115230000000 2102.530270000000 -4124.521000000000 0.000000000000 14127.727500000001 7218.115230000000 6696.063960000000 26 30 60 3412.000000000000 0.000000000000 0.000000000000 0.000000000000 11590.466800000000 2357.245850000000 0.000000000000 3412.000000000000 0.000000000000 -11590.466800000000 0.000000000000 -4226.889160000000 0.000000000000 0.000000000000 3412.000000000000 -2357.245850000000 4226.889160000000 0.000000000000 0.000000000000 -11590.466800000000 -2357.245850000000 41187.796900000001 -2853.077640000000 14341.535200000000 11590.466800000000 0.000000000000 4226.889160000000 -2853.077640000000 44716.816400000003 8010.299800000000 2357.245850000000 -4226.889160000000 0.000000000000 14341.535200000000 8010.299800000000 7119.812010000000 26 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9242.628909999999 -1180.214970000000 0.000000000000 5000.000000000000 0.000000000000 -9242.628909999999 0.000000000000 -4586.062500000000 0.000000000000 0.000000000000 5000.000000000000 1180.214970000000 4586.062500000000 0.000000000000 0.000000000000 -9242.628909999999 1180.214970000000 17972.062500000000 709.032227000000 8279.919920000000 9242.628909999999 0.000000000000 4586.062500000000 709.032227000000 22647.261699999999 -2244.934810000000 -1180.214970000000 -4586.062500000000 0.000000000000 8279.919920000000 -2244.934810000000 5697.924800000000 26 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9992.926760000000 -158.224533000000 0.000000000000 5000.000000000000 0.000000000000 -9992.926760000000 0.000000000000 897.849182000000 0.000000000000 0.000000000000 5000.000000000000 158.224533000000 -897.849182000000 0.000000000000 0.000000000000 -9992.926760000000 158.224533000000 21723.056600000000 75.747917200000 -1939.182130000000 9992.926760000000 0.000000000000 -897.849182000000 75.747917200000 21669.863300000001 -119.469833000000 -158.224533000000 897.849182000000 0.000000000000 -1939.182130000000 -119.469833000000 2568.974850000000 26 40 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16273.577100000000 3731.172360000000 0.000000000000 5000.000000000000 0.000000000000 -16273.577100000000 0.000000000000 -3878.802730000000 0.000000000000 0.000000000000 5000.000000000000 -3731.172360000000 3878.802730000000 0.000000000000 0.000000000000 -16273.577100000000 -3731.172360000000 56479.136700000003 -2654.928710000000 12779.416999999999 16273.577100000000 0.000000000000 3878.802730000000 -2654.928710000000 57031.757799999999 12183.134800000000 3731.172360000000 -3878.802730000000 0.000000000000 12779.416999999999 12183.134800000000 7226.781740000000 26 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16607.904299999998 4176.736820000000 0.000000000000 5000.000000000000 0.000000000000 -16607.904299999998 0.000000000000 -4003.508540000000 0.000000000000 0.000000000000 5000.000000000000 -4176.736820000000 4003.508540000000 0.000000000000 0.000000000000 -16607.904299999998 -4176.736820000000 59136.257799999999 -3049.650390000000 13386.384800000000 16607.904299999998 0.000000000000 4003.508540000000 -3049.650390000000 59186.363299999997 13865.636699999999 4176.736820000000 -4003.508540000000 0.000000000000 13386.384800000000 13865.636699999999 7788.071780000000 26 42 60 3751.000000000000 0.000000000000 0.000000000000 0.000000000000 12512.936500000000 3361.222410000000 0.000000000000 3751.000000000000 0.000000000000 -12512.936500000000 0.000000000000 -2949.673580000000 0.000000000000 0.000000000000 3751.000000000000 -3361.222410000000 2949.673580000000 0.000000000000 0.000000000000 -12512.936500000000 -3361.222410000000 45019.144500000002 -2429.597170000000 9952.287109999999 12512.936500000000 0.000000000000 2949.673580000000 -2429.597170000000 44688.769500000002 11175.684600000001 3361.222410000000 -2949.673580000000 0.000000000000 9952.287109999999 11175.684600000001 6117.671880000000 26 43 60 3350.000000000000 0.000000000000 0.000000000000 0.000000000000 11179.388700000000 3193.842530000000 0.000000000000 3350.000000000000 0.000000000000 -11179.388700000000 0.000000000000 -2515.390630000000 0.000000000000 0.000000000000 3350.000000000000 -3193.842530000000 2515.390630000000 0.000000000000 0.000000000000 -11179.388700000000 -3193.842530000000 40530.476600000002 -2261.785400000000 8492.758790000000 11179.388700000000 0.000000000000 2515.390630000000 -2261.785400000000 39714.117200000001 10630.547900000000 3193.842530000000 -2515.390630000000 0.000000000000 8492.758790000000 10630.547900000000 5535.103030000000 26 44 60 3057.000000000000 0.000000000000 0.000000000000 0.000000000000 10128.846700000000 3041.367190000000 0.000000000000 3057.000000000000 0.000000000000 -10128.846700000000 0.000000000000 -2197.252690000000 0.000000000000 0.000000000000 3057.000000000000 -3041.367190000000 2197.252690000000 0.000000000000 0.000000000000 -10128.846700000000 -3041.367190000000 36756.671900000001 -2078.073490000000 7422.690920000000 10128.846700000000 0.000000000000 2197.252690000000 -2078.073490000000 35721.839800000002 10051.149400000000 3041.367190000000 -2197.252690000000 0.000000000000 7422.690920000000 10051.149400000000 5203.647950000000 26 45 60 3191.000000000000 0.000000000000 0.000000000000 0.000000000000 10239.433600000000 3257.208500000000 0.000000000000 3191.000000000000 0.000000000000 -10239.433600000000 0.000000000000 -1645.650390000000 0.000000000000 0.000000000000 3191.000000000000 -3257.208500000000 1645.650390000000 0.000000000000 0.000000000000 -10239.433600000000 -3257.208500000000 36472.230499999998 -1626.034670000000 5551.938480000000 10239.433600000000 0.000000000000 1645.650390000000 -1626.034670000000 34403.914100000002 10452.088900000001 3257.208500000000 -1645.650390000000 0.000000000000 5551.938480000000 10452.088900000001 4741.234380000000 26 46 60 3553.000000000000 0.000000000000 0.000000000000 0.000000000000 10128.433600000000 3356.448240000000 0.000000000000 3553.000000000000 0.000000000000 -10128.433600000000 0.000000000000 -501.091400000000 0.000000000000 0.000000000000 3553.000000000000 -3356.448240000000 501.091400000000 0.000000000000 0.000000000000 -10128.433600000000 -3356.448240000000 32924.726600000002 -581.821533000000 1981.241940000000 10128.433600000000 0.000000000000 501.091400000000 -581.821533000000 30173.697300000000 9791.031250000000 3356.448240000000 -501.091400000000 0.000000000000 1981.241940000000 9791.031250000000 3918.473880000000 26 47 60 4088.000000000000 0.000000000000 0.000000000000 0.000000000000 10548.734399999999 3442.493900000000 0.000000000000 4088.000000000000 0.000000000000 -10548.734399999999 0.000000000000 295.408844000000 0.000000000000 0.000000000000 4088.000000000000 -3442.493900000000 -295.408844000000 0.000000000000 0.000000000000 -10548.734399999999 -3442.493900000000 31236.283200000002 85.750755300000 -255.159210000000 10548.734399999999 0.000000000000 -295.408844000000 85.750755300000 28461.011699999999 9257.601559999999 3442.493900000000 295.408844000000 0.000000000000 -255.159210000000 9257.601559999999 3614.243160000000 26 48 60 4582.000000000000 0.000000000000 0.000000000000 0.000000000000 10396.263700000000 3209.574220000000 0.000000000000 4582.000000000000 0.000000000000 -10396.263700000000 0.000000000000 1311.414790000000 0.000000000000 0.000000000000 4582.000000000000 -3209.574220000000 -1311.414790000000 0.000000000000 0.000000000000 -10396.263700000000 -3209.574220000000 26804.136699999999 755.246338000000 -2552.985600000000 10396.263700000000 0.000000000000 -1311.414790000000 755.246338000000 24973.757799999999 7609.626460000000 3209.574220000000 1311.414790000000 0.000000000000 -2552.985600000000 7609.626460000000 3276.668950000000 26 49 60 4524.000000000000 0.000000000000 0.000000000000 0.000000000000 9817.690430000001 2797.404300000000 0.000000000000 4524.000000000000 0.000000000000 -9817.690430000001 0.000000000000 1512.477420000000 0.000000000000 0.000000000000 4524.000000000000 -2797.404300000000 -1512.477420000000 0.000000000000 0.000000000000 -9817.690430000001 -2797.404300000000 23769.787100000001 805.453369000000 -2955.053710000000 9817.690430000001 0.000000000000 -1512.477420000000 805.453369000000 22573.019499999999 6304.753910000000 2797.404300000000 1512.477420000000 0.000000000000 -2955.053710000000 6304.753910000000 2826.797120000000 26 50 60 4321.000000000000 0.000000000000 0.000000000000 0.000000000000 10183.339800000000 2924.262210000000 0.000000000000 4321.000000000000 0.000000000000 -10183.339800000000 0.000000000000 906.274170000000 0.000000000000 0.000000000000 4321.000000000000 -2924.262210000000 -906.274170000000 0.000000000000 0.000000000000 -10183.339800000000 -2924.262210000000 27086.322300000000 471.572968000000 -1816.068970000000 10183.339800000000 0.000000000000 -906.274170000000 471.572968000000 25033.418000000001 7264.916990000000 2924.262210000000 906.274170000000 0.000000000000 -1816.068970000000 7264.916990000000 2989.976070000000 26 51 60 2895.000000000000 0.000000000000 0.000000000000 0.000000000000 7676.740230000000 2565.435060000000 0.000000000000 2895.000000000000 0.000000000000 -7676.740230000000 0.000000000000 191.891937000000 0.000000000000 0.000000000000 2895.000000000000 -2565.435060000000 -191.891937000000 0.000000000000 0.000000000000 -7676.740230000000 -2565.435060000000 23147.304700000001 99.044441200000 -348.258698000000 7676.740230000000 0.000000000000 -191.891937000000 99.044441200000 20833.505900000000 7002.310060000000 2565.435060000000 191.891937000000 0.000000000000 -348.258698000000 7002.310060000000 2539.371830000000 26 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11097.665000000001 2064.868900000000 0.000000000000 5000.000000000000 0.000000000000 -11097.665000000001 0.000000000000 1557.770020000000 0.000000000000 0.000000000000 5000.000000000000 -2064.868900000000 -1557.770020000000 0.000000000000 0.000000000000 -11097.665000000001 -2064.868900000000 27645.847699999998 119.937637000000 -3030.602540000000 11097.665000000001 0.000000000000 -1557.770020000000 119.937637000000 26218.283200000002 5234.866700000000 2064.868900000000 1557.770020000000 0.000000000000 -3030.602540000000 5234.866700000000 3289.078370000000 26 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10416.511699999999 1282.896610000000 0.000000000000 5000.000000000000 0.000000000000 -10416.511699999999 0.000000000000 1801.360840000000 0.000000000000 0.000000000000 5000.000000000000 -1282.896610000000 -1801.360840000000 0.000000000000 0.000000000000 -10416.511699999999 -1282.896610000000 23664.171900000001 184.297745000000 -3468.936280000000 10416.511699999999 0.000000000000 -1801.360840000000 184.297745000000 23118.857400000001 2950.401860000000 1282.896610000000 1801.360840000000 0.000000000000 -3468.936280000000 2950.401860000000 2659.414310000000 26 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9594.557620000000 -776.873962000000 0.000000000000 5000.000000000000 0.000000000000 -9594.557620000000 0.000000000000 -265.144897000000 0.000000000000 0.000000000000 5000.000000000000 776.873962000000 265.144897000000 0.000000000000 0.000000000000 -9594.557620000000 776.873962000000 20016.753900000000 226.706802000000 150.372620000000 9594.557620000000 0.000000000000 265.144897000000 226.706802000000 20269.884800000000 -1442.710940000000 -776.873962000000 -265.144897000000 0.000000000000 150.372620000000 -1442.710940000000 2722.699220000000 26 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9674.449220000000 -2122.867920000000 0.000000000000 5000.000000000000 0.000000000000 -9674.449220000000 0.000000000000 -1295.107180000000 0.000000000000 0.000000000000 5000.000000000000 2122.867920000000 1295.107180000000 0.000000000000 0.000000000000 -9674.449220000000 2122.867920000000 20340.081999999999 -62.777713800000 2082.745610000000 9674.449220000000 0.000000000000 1295.107180000000 -62.777713800000 21268.138700000000 -4275.704590000000 -2122.867920000000 -1295.107180000000 0.000000000000 2082.745610000000 -4275.704590000000 3445.829590000000 26 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9880.376950000000 -2054.748050000000 0.000000000000 5000.000000000000 0.000000000000 -9880.376950000000 0.000000000000 -1733.941530000000 0.000000000000 0.000000000000 5000.000000000000 2054.748050000000 1733.941530000000 0.000000000000 0.000000000000 -9880.376950000000 2054.748050000000 21128.462899999999 -1.346705910000 2990.845950000000 9880.376950000000 0.000000000000 1733.941530000000 -1.346705910000 22428.205099999999 -4221.702640000000 -2054.748050000000 -1733.941530000000 0.000000000000 2990.845950000000 -4221.702640000000 3675.018800000000 26 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10102.540999999999 -1861.795900000000 0.000000000000 5000.000000000000 0.000000000000 -10102.540999999999 0.000000000000 -2044.162230000000 0.000000000000 0.000000000000 5000.000000000000 1861.795900000000 2044.162230000000 0.000000000000 0.000000000000 -10102.540999999999 1861.795900000000 21934.377000000000 161.443237000000 3645.307620000000 10102.540999999999 0.000000000000 2044.162230000000 161.443237000000 23378.052700000000 -3929.405030000000 -1861.795900000000 -2044.162230000000 0.000000000000 3645.307620000000 -3929.405030000000 3468.473390000000 26 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10054.419900000001 -858.833069000000 0.000000000000 5000.000000000000 0.000000000000 -10054.419900000001 0.000000000000 -3145.451900000000 0.000000000000 0.000000000000 5000.000000000000 858.833069000000 3145.451900000000 0.000000000000 0.000000000000 -10054.419900000001 858.833069000000 21263.445299999999 414.325287000000 5743.869630000000 10054.419900000001 0.000000000000 3145.451900000000 414.325287000000 24084.134800000000 -1773.467650000000 -858.833069000000 -3145.451900000000 0.000000000000 5743.869630000000 -1773.467650000000 3509.423580000000 26 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10243.168900000001 -238.592133000000 0.000000000000 5000.000000000000 0.000000000000 -10243.168900000001 0.000000000000 -3026.870120000000 0.000000000000 0.000000000000 5000.000000000000 238.592133000000 3026.870120000000 0.000000000000 0.000000000000 -10243.168900000001 238.592133000000 21922.021499999999 253.478531000000 5761.124510000000 10243.168900000001 0.000000000000 3026.870120000000 253.478531000000 24407.808600000000 -377.726349000000 -238.592133000000 -3026.870120000000 0.000000000000 5761.124510000000 -377.726349000000 2935.381840000000 27 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15741.153300000000 4323.479490000000 0.000000000000 5000.000000000000 0.000000000000 -15741.153300000000 0.000000000000 -408.644684000000 0.000000000000 0.000000000000 5000.000000000000 -4323.479490000000 408.644684000000 0.000000000000 0.000000000000 -15741.153300000000 -4323.479490000000 53898.777300000002 63.752910600000 1242.911740000000 15741.153300000000 0.000000000000 408.644684000000 63.752910600000 50897.390599999999 13728.453100000001 4323.479490000000 -408.644684000000 0.000000000000 1242.911740000000 13728.453100000001 5373.604980000000 27 31 60 4547.000000000000 0.000000000000 0.000000000000 0.000000000000 14279.481400000001 2382.848140000000 0.000000000000 4547.000000000000 0.000000000000 -14279.481400000001 0.000000000000 -1534.682250000000 0.000000000000 0.000000000000 4547.000000000000 -2382.848140000000 1534.682250000000 0.000000000000 0.000000000000 -14279.481400000001 -2382.848140000000 46744.027300000002 -762.647217000000 4839.528810000000 14279.481400000001 0.000000000000 1534.682250000000 -762.647217000000 46091.835899999998 7422.610840000000 2382.848140000000 -1534.682250000000 0.000000000000 4839.528810000000 7422.610840000000 2887.572270000000 27 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14023.409200000000 1272.340940000000 0.000000000000 5000.000000000000 0.000000000000 -14023.409200000000 0.000000000000 -2535.085450000000 0.000000000000 0.000000000000 5000.000000000000 -1272.340940000000 2535.085450000000 0.000000000000 0.000000000000 -14023.409200000000 -1272.340940000000 41487.347699999998 -622.066345000000 6805.102540000000 14023.409200000000 0.000000000000 2535.085450000000 -622.066345000000 42502.101600000002 3923.164310000000 1272.340940000000 -2535.085450000000 0.000000000000 6805.102540000000 3923.164310000000 2472.199460000000 27 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9641.160159999999 -1559.513920000000 0.000000000000 5000.000000000000 0.000000000000 -9641.160159999999 0.000000000000 1076.610470000000 0.000000000000 0.000000000000 5000.000000000000 1559.513920000000 -1076.610470000000 0.000000000000 0.000000000000 -9641.160159999999 1559.513920000000 19832.418000000001 -563.400513000000 -2401.045650000000 9641.160159999999 0.000000000000 -1076.610470000000 -563.400513000000 20208.421900000001 -3067.680660000000 -1559.513920000000 1076.610470000000 0.000000000000 -2401.045650000000 -3067.680660000000 2222.698970000000 27 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10582.378900000000 -991.411926000000 0.000000000000 5000.000000000000 0.000000000000 -10582.378900000000 0.000000000000 166.006348000000 0.000000000000 0.000000000000 5000.000000000000 991.411926000000 -166.006348000000 0.000000000000 0.000000000000 -10582.378900000000 991.411926000000 23929.871100000000 -223.501160000000 -916.982239000000 10582.378900000000 0.000000000000 -166.006348000000 -223.501160000000 24963.400399999999 -2037.971560000000 -991.411926000000 166.006348000000 0.000000000000 -916.982239000000 -2037.971560000000 2083.210450000000 27 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9970.486330000000 -659.494690000000 0.000000000000 5000.000000000000 0.000000000000 -9970.486330000000 0.000000000000 -640.685364000000 0.000000000000 0.000000000000 5000.000000000000 659.494690000000 640.685364000000 0.000000000000 0.000000000000 -9970.486330000000 659.494690000000 21256.083999999999 15.155081700000 805.157837000000 9970.486330000000 0.000000000000 640.685364000000 15.155081700000 22631.175800000001 -1132.660030000000 -659.494690000000 -640.685364000000 0.000000000000 805.157837000000 -1132.660030000000 1943.647950000000 27 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9679.919920000000 -399.727356000000 0.000000000000 5000.000000000000 0.000000000000 -9679.919920000000 0.000000000000 -434.860809000000 0.000000000000 0.000000000000 5000.000000000000 399.727356000000 434.860809000000 0.000000000000 0.000000000000 -9679.919920000000 399.727356000000 19660.523399999998 69.122192400000 500.739655000000 9679.919920000000 0.000000000000 434.860809000000 69.122192400000 21333.380900000000 -560.494080000000 -399.727356000000 -434.860809000000 0.000000000000 500.739655000000 -560.494080000000 2193.237300000000 27 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14969.699199999999 4564.048830000000 0.000000000000 5000.000000000000 0.000000000000 -14969.699199999999 0.000000000000 1452.346190000000 0.000000000000 0.000000000000 5000.000000000000 -4564.048830000000 -1452.346190000000 0.000000000000 0.000000000000 -14969.699199999999 -4564.048830000000 50089.628900000003 1447.697390000000 -3992.957280000000 14969.699199999999 0.000000000000 -1452.346190000000 1447.697390000000 47877.972699999998 13977.588900000001 4564.048830000000 1452.346190000000 0.000000000000 -3992.957280000000 13977.588900000001 7438.839840000000 27 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14806.252000000000 4602.981930000000 0.000000000000 5000.000000000000 0.000000000000 -14806.252000000000 0.000000000000 2459.285160000000 0.000000000000 0.000000000000 5000.000000000000 -4602.981930000000 -2459.285160000000 0.000000000000 0.000000000000 -14806.252000000000 -4602.981930000000 49259.144500000002 2332.723390000000 -6960.033690000000 14806.252000000000 0.000000000000 -2459.285160000000 2332.723390000000 46785.082000000002 13995.525400000000 4602.981930000000 2459.285160000000 0.000000000000 -6960.033690000000 13995.525400000000 7300.221190000000 27 43 60 4967.000000000000 0.000000000000 0.000000000000 0.000000000000 14758.424800000001 4931.095700000000 0.000000000000 4967.000000000000 0.000000000000 -14758.424800000001 0.000000000000 2842.074950000000 0.000000000000 0.000000000000 4967.000000000000 -4931.095700000000 -2842.074950000000 0.000000000000 0.000000000000 -14758.424800000001 -4931.095700000000 49767.960899999998 2874.259770000000 -8149.750000000000 14758.424800000001 0.000000000000 -2842.074950000000 2874.259770000000 46929.910199999998 15002.230500000000 4931.095700000000 2842.074950000000 0.000000000000 -8149.750000000000 15002.230500000000 7854.021970000000 27 44 60 4015.000000000000 0.000000000000 0.000000000000 0.000000000000 11711.004900000000 3916.613530000000 0.000000000000 4015.000000000000 0.000000000000 -11711.004900000000 0.000000000000 2752.206300000000 0.000000000000 0.000000000000 4015.000000000000 -3916.613530000000 -2752.206300000000 0.000000000000 0.000000000000 -11711.004900000000 -3916.613530000000 38853.570299999999 2667.154790000000 -7797.858890000000 11711.004900000000 0.000000000000 -2752.206300000000 2667.154790000000 37023.191400000003 11728.301799999999 3916.613530000000 2752.206300000000 0.000000000000 -7797.858890000000 11728.301799999999 6516.126950000000 27 45 60 2546.000000000000 0.000000000000 0.000000000000 0.000000000000 6836.120120000000 2260.505860000000 0.000000000000 2546.000000000000 0.000000000000 -6836.120120000000 0.000000000000 2215.970700000000 0.000000000000 0.000000000000 2546.000000000000 -2260.505860000000 -2215.970700000000 0.000000000000 0.000000000000 -6836.120120000000 -2260.505860000000 21051.127000000000 2010.187870000000 -5925.996580000000 6836.120120000000 0.000000000000 -2215.970700000000 2010.187870000000 20864.498000000000 6322.684080000000 2260.505860000000 2215.970700000000 0.000000000000 -5925.996580000000 6322.684080000000 4230.930660000000 27 59 60 4245.000000000000 0.000000000000 0.000000000000 0.000000000000 7700.877930000000 -862.987549000000 0.000000000000 4245.000000000000 0.000000000000 -7700.877930000000 0.000000000000 268.660278000000 0.000000000000 0.000000000000 4245.000000000000 862.987549000000 -268.660278000000 0.000000000000 0.000000000000 -7700.877930000000 862.987549000000 14604.324199999999 -167.611588000000 -681.837158000000 7700.877930000000 0.000000000000 -268.660278000000 -167.611588000000 15584.571300000000 -1607.685180000000 -862.987549000000 268.660278000000 0.000000000000 -681.837158000000 -1607.685180000000 1619.220090000000 28 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13073.800800000001 -911.664124000000 0.000000000000 5000.000000000000 0.000000000000 -13073.800800000001 0.000000000000 -2959.905520000000 0.000000000000 0.000000000000 5000.000000000000 911.664124000000 2959.905520000000 0.000000000000 0.000000000000 -13073.800800000001 911.664124000000 35876.156300000002 724.444031000000 8187.674800000000 13073.800800000001 0.000000000000 2959.905520000000 724.444031000000 38157.941400000003 -2414.430420000000 -911.664124000000 -2959.905520000000 0.000000000000 8187.674800000000 -2414.430420000000 3282.675050000000 28 37 60 3996.000000000000 0.000000000000 0.000000000000 0.000000000000 7736.222660000000 -1795.875240000000 0.000000000000 3996.000000000000 0.000000000000 -7736.222660000000 0.000000000000 208.696777000000 0.000000000000 0.000000000000 3996.000000000000 1795.875240000000 -208.696777000000 0.000000000000 0.000000000000 -7736.222660000000 1795.875240000000 16449.478500000001 -369.707245000000 -885.169312000000 7736.222660000000 0.000000000000 -208.696777000000 -369.707245000000 16633.261699999999 -3573.886230000000 -1795.875240000000 208.696777000000 0.000000000000 -885.169312000000 -3573.886230000000 2101.580570000000 28 38 60 3104.000000000000 0.000000000000 0.000000000000 0.000000000000 6079.960450000000 -1161.684570000000 0.000000000000 3104.000000000000 0.000000000000 -6079.960450000000 0.000000000000 -416.993011000000 0.000000000000 0.000000000000 3104.000000000000 1161.684570000000 416.993011000000 0.000000000000 0.000000000000 -6079.960450000000 1161.684570000000 13034.321300000000 53.964622500000 569.219849000000 6079.960450000000 0.000000000000 416.993011000000 53.964622500000 13350.279300000000 -2378.327640000000 -1161.684570000000 -416.993011000000 0.000000000000 569.219849000000 -2378.327640000000 1375.992550000000 28 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12059.838900000001 3774.888430000000 0.000000000000 5000.000000000000 0.000000000000 -12059.838900000001 0.000000000000 2545.040280000000 0.000000000000 0.000000000000 5000.000000000000 -3774.888430000000 -2545.040280000000 0.000000000000 0.000000000000 -12059.838900000001 -3774.888430000000 32859.710899999998 1892.586430000000 -5933.618650000000 12059.838900000001 0.000000000000 -2545.040280000000 1892.586430000000 31755.613300000001 9420.778319999999 3774.888430000000 2545.040280000000 0.000000000000 -5933.618650000000 9420.778319999999 5641.435060000000 28 44 60 4906.000000000000 0.000000000000 0.000000000000 0.000000000000 11603.357400000001 3410.565190000000 0.000000000000 4906.000000000000 0.000000000000 -11603.357400000001 0.000000000000 3232.601810000000 0.000000000000 0.000000000000 4906.000000000000 -3410.565190000000 -3232.601810000000 0.000000000000 0.000000000000 -11603.357400000001 -3410.565190000000 30734.701200000000 2306.516850000000 -7521.583010000000 11603.357400000001 0.000000000000 -3232.601810000000 2306.516850000000 30490.494100000000 8379.766600000001 3410.565190000000 3232.601810000000 0.000000000000 -7521.583010000000 8379.766600000001 5530.616700000000 28 45 60 1965.000000000000 0.000000000000 0.000000000000 0.000000000000 4485.526860000000 1312.363890000000 0.000000000000 1965.000000000000 0.000000000000 -4485.526860000000 0.000000000000 1682.404790000000 0.000000000000 0.000000000000 1965.000000000000 -1312.363890000000 -1682.404790000000 0.000000000000 0.000000000000 -4485.526860000000 -1312.363890000000 11392.018599999999 1208.541380000000 -3860.907470000000 4485.526860000000 0.000000000000 -1682.404790000000 1208.541380000000 11880.762699999999 3093.143800000000 1312.363890000000 1682.404790000000 0.000000000000 -3860.907470000000 3093.143800000000 2579.508060000000 29 32 60 4900.000000000000 0.000000000000 0.000000000000 0.000000000000 10956.043900000001 -2459.214600000000 0.000000000000 4900.000000000000 0.000000000000 -10956.043900000001 0.000000000000 -3377.797850000000 0.000000000000 0.000000000000 4900.000000000000 2459.214600000000 3377.797850000000 0.000000000000 0.000000000000 -10956.043900000001 2459.214600000000 26205.222699999998 1869.924930000000 7706.157710000000 10956.043900000001 0.000000000000 3377.797850000000 1869.924930000000 27550.761699999999 -5628.765140000000 -2459.214600000000 -3377.797850000000 0.000000000000 7706.157710000000 -5628.765140000000 4449.654790000000 29 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10342.584999999999 2575.674560000000 0.000000000000 5000.000000000000 0.000000000000 -10342.584999999999 0.000000000000 1926.766480000000 0.000000000000 0.000000000000 5000.000000000000 -2575.674560000000 -1926.766480000000 0.000000000000 0.000000000000 -10342.584999999999 -2575.674560000000 23243.324199999999 1027.425900000000 -3963.885500000000 10342.584999999999 0.000000000000 -1926.766480000000 1027.425900000000 22900.527300000002 5462.643070000000 2575.674560000000 1926.766480000000 0.000000000000 -3963.885500000000 5462.643070000000 3048.159180000000 29 45 60 2331.000000000000 0.000000000000 0.000000000000 0.000000000000 4614.600100000000 1063.880860000000 0.000000000000 2331.000000000000 0.000000000000 -4614.600100000000 0.000000000000 1402.013310000000 0.000000000000 0.000000000000 2331.000000000000 -1063.880860000000 -1402.013310000000 0.000000000000 0.000000000000 -4614.600100000000 -1063.880860000000 9868.885740000000 716.162415000000 -2798.939940000000 4614.600100000000 0.000000000000 -1402.013310000000 716.162415000000 10149.523400000000 2183.383060000000 1063.880860000000 1402.013310000000 0.000000000000 -2798.939940000000 2183.383060000000 1623.023800000000 30 33 60 3209.000000000000 0.000000000000 0.000000000000 0.000000000000 6601.636230000000 -2855.446780000000 0.000000000000 3209.000000000000 0.000000000000 -6601.636230000000 0.000000000000 -3341.568360000000 0.000000000000 0.000000000000 3209.000000000000 2855.446780000000 3341.568360000000 0.000000000000 0.000000000000 -6601.636230000000 2855.446780000000 16200.947300000000 2951.398680000000 6972.467290000000 6601.636230000000 0.000000000000 3341.568360000000 2951.398680000000 17391.839800000002 -5849.412600000000 -2855.446780000000 -3341.568360000000 0.000000000000 6972.467290000000 -5849.412600000000 6293.825200000000 30 44 60 4659.000000000000 0.000000000000 0.000000000000 0.000000000000 7102.924320000000 947.745850000000 0.000000000000 4659.000000000000 0.000000000000 -7102.924320000000 0.000000000000 1850.293460000000 0.000000000000 0.000000000000 4659.000000000000 -947.745850000000 -1850.293460000000 0.000000000000 0.000000000000 -7102.924320000000 -947.745850000000 11418.920899999999 430.234802000000 -2840.974120000000 7102.924320000000 0.000000000000 -1850.293460000000 430.234802000000 11948.609399999999 1549.512820000000 947.745850000000 1850.293460000000 0.000000000000 -2840.974120000000 1549.512820000000 1518.559080000000 31 40 60 3858.000000000000 0.000000000000 0.000000000000 0.000000000000 5237.057130000000 -516.458191000000 0.000000000000 3858.000000000000 0.000000000000 -5237.057130000000 0.000000000000 -170.118011000000 0.000000000000 0.000000000000 3858.000000000000 516.458191000000 170.118011000000 0.000000000000 0.000000000000 -5237.057130000000 516.458191000000 7800.902340000000 -45.392429400000 266.264374000000 5237.057130000000 0.000000000000 170.118011000000 -45.392429400000 7433.527340000000 -654.900208000000 -516.458191000000 -170.118011000000 0.000000000000 266.264374000000 -654.900208000000 783.951843000000 31 41 60 4043.000000000000 0.000000000000 0.000000000000 0.000000000000 5113.072750000000 71.542701700000 0.000000000000 4043.000000000000 0.000000000000 -5113.072750000000 0.000000000000 302.766144000000 0.000000000000 0.000000000000 4043.000000000000 -71.542701700000 -302.766144000000 0.000000000000 0.000000000000 -5113.072750000000 -71.542701700000 7127.114750000000 -123.034630000000 -281.443329000000 5113.072750000000 0.000000000000 -302.766144000000 -123.034630000000 6944.087890000000 291.274078000000 71.542701700000 302.766144000000 0.000000000000 -281.443329000000 291.274078000000 809.626587000000 31 42 60 3314.000000000000 0.000000000000 0.000000000000 0.000000000000 4081.544430000000 224.123749000000 0.000000000000 3314.000000000000 0.000000000000 -4081.544430000000 0.000000000000 564.100708000000 0.000000000000 0.000000000000 3314.000000000000 -224.123749000000 -564.100708000000 0.000000000000 0.000000000000 -4081.544430000000 -224.123749000000 5513.422850000000 5.993037700000 -652.419128000000 4081.544430000000 0.000000000000 -564.100708000000 5.993037700000 5382.635250000000 440.874664000000 224.123749000000 564.100708000000 0.000000000000 -652.419128000000 440.874664000000 614.808655000000 31 43 60 2824.000000000000 0.000000000000 0.000000000000 0.000000000000 3494.417480000000 609.804016000000 0.000000000000 2824.000000000000 0.000000000000 -3494.417480000000 0.000000000000 807.929321000000 0.000000000000 0.000000000000 2824.000000000000 -609.804016000000 -807.929321000000 0.000000000000 0.000000000000 -3494.417480000000 -609.804016000000 4724.755860000000 187.101746000000 -997.904907000000 3494.417480000000 0.000000000000 -807.929321000000 187.101746000000 4729.132320000000 851.936523000000 609.804016000000 807.929321000000 0.000000000000 -997.904907000000 851.936523000000 663.883545000000 32 34 60 2783.000000000000 0.000000000000 0.000000000000 0.000000000000 3247.690190000000 -447.092651000000 0.000000000000 2783.000000000000 0.000000000000 -3247.690190000000 0.000000000000 -2031.516850000000 0.000000000000 0.000000000000 2783.000000000000 447.092651000000 2031.516850000000 0.000000000000 0.000000000000 -3247.690190000000 447.092651000000 4035.384520000000 263.597198000000 2388.255860000000 3247.690190000000 0.000000000000 2031.516850000000 263.597198000000 5476.643070000000 -468.622040000000 -447.092651000000 -2031.516850000000 0.000000000000 2388.255860000000 -468.622040000000 1758.859860000000 32 38 60 4332.000000000000 0.000000000000 0.000000000000 0.000000000000 5279.241700000000 -1014.156430000000 0.000000000000 4332.000000000000 0.000000000000 -5279.241700000000 0.000000000000 -2463.448490000000 0.000000000000 0.000000000000 4332.000000000000 1014.156430000000 2463.448490000000 0.000000000000 0.000000000000 -5279.241700000000 1014.156430000000 6959.493650000000 449.992737000000 2835.105470000000 5279.241700000000 0.000000000000 2463.448490000000 449.992737000000 8340.524410000000 -1267.027220000000 -1014.156430000000 -2463.448490000000 0.000000000000 2835.105470000000 -1267.027220000000 2059.222660000000 32 39 60 2813.000000000000 0.000000000000 0.000000000000 0.000000000000 3268.511960000000 -650.404907000000 0.000000000000 2813.000000000000 0.000000000000 -3268.511960000000 0.000000000000 -1823.893680000000 0.000000000000 0.000000000000 2813.000000000000 650.404907000000 1823.893680000000 0.000000000000 0.000000000000 -3268.511960000000 650.404907000000 4121.187990000000 377.343567000000 2063.054440000000 3268.511960000000 0.000000000000 1823.893680000000 377.343567000000 5215.424320000000 -747.822571000000 -650.404907000000 -1823.893680000000 0.000000000000 2063.054440000000 -747.822571000000 1508.473880000000 32 40 60 1455.000000000000 0.000000000000 0.000000000000 0.000000000000 1920.094600000000 12.701665900000 0.000000000000 1455.000000000000 0.000000000000 -1920.094600000000 0.000000000000 509.587219000000 0.000000000000 0.000000000000 1455.000000000000 -12.701665900000 -509.587219000000 0.000000000000 0.000000000000 -1920.094600000000 -12.701665900000 2659.166750000000 8.534535410000 -678.837341000000 1920.094600000000 0.000000000000 -509.587219000000 8.534535410000 2842.599610000000 31.722477000000 12.701665900000 509.587219000000 0.000000000000 -678.837341000000 31.722477000000 299.047180000000 33 37 60 4239.000000000000 0.000000000000 0.000000000000 0.000000000000 4831.073240000000 -142.134186000000 0.000000000000 4239.000000000000 0.000000000000 -4831.073240000000 0.000000000000 -2600.692870000000 0.000000000000 0.000000000000 4239.000000000000 142.134186000000 2600.692870000000 0.000000000000 0.000000000000 -4831.073240000000 142.134186000000 5636.690920000000 117.621231000000 2937.361080000000 4831.073240000000 0.000000000000 2600.692870000000 117.621231000000 7427.650880000000 -116.184441000000 -142.134186000000 -2600.692870000000 0.000000000000 2937.361080000000 -116.184441000000 1977.063960000000 33 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6119.649900000000 60.364738500000 0.000000000000 5000.000000000000 0.000000000000 -6119.649900000000 0.000000000000 -2657.678220000000 0.000000000000 0.000000000000 5000.000000000000 -60.364738500000 2657.678220000000 0.000000000000 0.000000000000 -6119.649900000000 -60.364738500000 7881.664550000000 -129.565414000000 3173.012940000000 6119.649900000000 0.000000000000 2657.678220000000 -129.565414000000 9625.662109999999 174.998474000000 60.364738500000 -2657.678220000000 0.000000000000 3173.012940000000 174.998474000000 2253.555180000000 33 39 60 4662.000000000000 0.000000000000 0.000000000000 0.000000000000 5645.892580000000 131.583023000000 0.000000000000 4662.000000000000 0.000000000000 -5645.892580000000 0.000000000000 -2490.021000000000 0.000000000000 0.000000000000 4662.000000000000 -131.583023000000 2490.021000000000 0.000000000000 0.000000000000 -5645.892580000000 -131.583023000000 7126.921390000000 -151.243896000000 2986.024660000000 5645.892580000000 0.000000000000 2490.021000000000 -151.243896000000 8711.853520000001 236.283829000000 131.583023000000 -2490.021000000000 0.000000000000 2986.024660000000 236.283829000000 1948.351440000000 33 56 60 2500.000000000000 0.000000000000 0.000000000000 0.000000000000 2875.261720000000 -54.338436100000 0.000000000000 2500.000000000000 0.000000000000 -2875.261720000000 0.000000000000 -1988.836180000000 0.000000000000 0.000000000000 2500.000000000000 54.338436100000 1988.836180000000 0.000000000000 0.000000000000 -2875.261720000000 54.338436100000 3454.369630000000 -3.209277630000 2329.404300000000 2875.261720000000 0.000000000000 1988.836180000000 -3.209277630000 5056.021000000000 3.244737630000 -54.338436100000 -1988.836180000000 0.000000000000 2329.404300000000 3.244737630000 1801.913330000000 33 57 60 2734.000000000000 0.000000000000 0.000000000000 0.000000000000 3110.287350000000 -90.890258800000 0.000000000000 2734.000000000000 0.000000000000 -3110.287350000000 0.000000000000 -2078.771240000000 0.000000000000 0.000000000000 2734.000000000000 90.890258800000 2078.771240000000 0.000000000000 0.000000000000 -3110.287350000000 90.890258800000 3689.967290000000 13.147718400000 2414.612550000000 3110.287350000000 0.000000000000 2078.771240000000 13.147718400000 5310.670900000000 -34.908863100000 -90.890258800000 -2078.771240000000 0.000000000000 2414.612550000000 -34.908863100000 1824.075560000000 33 58 60 2568.000000000000 0.000000000000 0.000000000000 0.000000000000 2938.928470000000 -46.307277700000 0.000000000000 2568.000000000000 0.000000000000 -2938.928470000000 0.000000000000 -1914.118290000000 0.000000000000 0.000000000000 2568.000000000000 46.307277700000 1914.118290000000 0.000000000000 0.000000000000 -2938.928470000000 46.307277700000 3487.543700000000 -9.551615720000 2231.721440000000 2938.928470000000 0.000000000000 1914.118290000000 -9.551615720000 4964.810060000000 4.689830300000 -46.307277700000 -1914.118290000000 0.000000000000 2231.721440000000 4.689830300000 1641.421020000000 34 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8337.803710000000 481.938629000000 0.000000000000 5000.000000000000 0.000000000000 -8337.803710000000 0.000000000000 -4793.095210000000 0.000000000000 0.000000000000 5000.000000000000 -481.938629000000 4793.095210000000 0.000000000000 0.000000000000 -8337.803710000000 -481.938629000000 15094.334000000001 -763.387695000000 8231.022460000000 8337.803710000000 0.000000000000 4793.095210000000 -763.387695000000 19242.970700000002 1093.293090000000 481.938629000000 -4793.095210000000 0.000000000000 8231.022460000000 1093.293090000000 5956.974120000000 34 36 60 3584.000000000000 0.000000000000 0.000000000000 0.000000000000 4604.001950000000 -882.859619000000 0.000000000000 3584.000000000000 0.000000000000 -4604.001950000000 0.000000000000 -1708.391850000000 0.000000000000 0.000000000000 3584.000000000000 882.859619000000 1708.391850000000 0.000000000000 0.000000000000 -4604.001950000000 882.859619000000 6638.371090000000 547.830078000000 2419.267330000000 4604.001950000000 0.000000000000 1708.391850000000 547.830078000000 7574.534670000000 -1167.172000000000 -882.859619000000 -1708.391850000000 0.000000000000 2419.267330000000 -1167.172000000000 1977.185790000000 34 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6311.652830000000 -352.938599000000 0.000000000000 5000.000000000000 0.000000000000 -6311.652830000000 0.000000000000 -438.685730000000 0.000000000000 0.000000000000 5000.000000000000 352.938599000000 438.685730000000 0.000000000000 0.000000000000 -6311.652830000000 352.938599000000 8241.319340000000 23.561050400000 753.237000000000 6311.652830000000 0.000000000000 438.685730000000 23.561050400000 9035.133790000000 -390.738586000000 -352.938599000000 -438.685730000000 0.000000000000 753.237000000000 -390.738586000000 1110.746830000000 34 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6638.903320000000 40.368091600000 0.000000000000 5000.000000000000 0.000000000000 -6638.903320000000 0.000000000000 -497.604095000000 0.000000000000 0.000000000000 5000.000000000000 -40.368091600000 497.604095000000 0.000000000000 0.000000000000 -6638.903320000000 -40.368091600000 9257.015630000000 -206.374069000000 952.349915000000 6638.903320000000 0.000000000000 497.604095000000 -206.374069000000 10125.227500000001 241.193115000000 40.368091600000 -497.604095000000 0.000000000000 952.349915000000 241.193115000000 1340.676270000000 34 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6736.262700000000 154.510864000000 0.000000000000 5000.000000000000 0.000000000000 -6736.262700000000 0.000000000000 -513.191528000000 0.000000000000 0.000000000000 5000.000000000000 -154.510864000000 513.191528000000 0.000000000000 0.000000000000 -6736.262700000000 -154.510864000000 9632.354490000000 -294.847931000000 1029.578610000000 6736.262700000000 0.000000000000 513.191528000000 -294.847931000000 10429.953100000001 455.300323000000 154.510864000000 -513.191528000000 0.000000000000 1029.578610000000 455.300323000000 1381.574580000000 34 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7716.146480000000 225.185654000000 0.000000000000 5000.000000000000 0.000000000000 -7716.146480000000 0.000000000000 -3999.379150000000 0.000000000000 0.000000000000 5000.000000000000 -225.185654000000 3999.379150000000 0.000000000000 0.000000000000 -7716.146480000000 -225.185654000000 12746.790999999999 -381.193085000000 6540.400390000000 7716.146480000000 0.000000000000 3999.379150000000 -381.193085000000 16087.295899999999 548.354858000000 225.185654000000 -3999.379150000000 0.000000000000 6540.400390000000 548.354858000000 4449.923340000000 34 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7576.058590000000 784.685303000000 0.000000000000 5000.000000000000 0.000000000000 -7576.058590000000 0.000000000000 -2634.687990000000 0.000000000000 0.000000000000 5000.000000000000 -784.685303000000 2634.687990000000 0.000000000000 0.000000000000 -7576.058590000000 -784.685303000000 12432.771500000001 -731.888428000000 4480.131350000000 7576.058590000000 0.000000000000 2634.687990000000 -731.888428000000 14292.036099999999 1549.395870000000 784.685303000000 -2634.687990000000 0.000000000000 4480.131350000000 1549.395870000000 2938.775390000000 34 59 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7260.073240000000 385.921021000000 0.000000000000 5000.000000000000 0.000000000000 -7260.073240000000 0.000000000000 -3161.966550000000 0.000000000000 0.000000000000 5000.000000000000 -385.921021000000 3161.966550000000 0.000000000000 0.000000000000 -7260.073240000000 -385.921021000000 11008.737300000001 -524.853088000000 5032.866700000000 7260.073240000000 0.000000000000 3161.966550000000 -524.853088000000 13846.599600000000 760.803345000000 385.921021000000 -3161.966550000000 0.000000000000 5032.866700000000 760.803345000000 3251.902340000000 35 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9414.900390000001 80.718330400000 0.000000000000 5000.000000000000 0.000000000000 -9414.900390000001 0.000000000000 -1209.413570000000 0.000000000000 0.000000000000 5000.000000000000 -80.718330400000 1209.413570000000 0.000000000000 0.000000000000 -9414.900390000001 -80.718330400000 20189.574199999999 353.477997000000 3329.179690000000 9414.900390000001 0.000000000000 1209.413570000000 353.477997000000 21530.466799999998 596.471313000000 80.718330400000 -1209.413570000000 0.000000000000 3329.179690000000 596.471313000000 2679.871830000000 35 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8434.850590000000 197.813065000000 0.000000000000 5000.000000000000 0.000000000000 -8434.850590000000 0.000000000000 -1864.469240000000 0.000000000000 0.000000000000 5000.000000000000 -197.813065000000 1864.469240000000 0.000000000000 0.000000000000 -8434.850590000000 -197.813065000000 16157.398400000000 58.711811100000 3581.783690000000 8434.850590000000 0.000000000000 1864.469240000000 58.711811100000 17724.564500000000 943.270630000000 197.813065000000 -1864.469240000000 0.000000000000 3581.783690000000 943.270630000000 3168.093510000000 35 48 60 4593.000000000000 0.000000000000 0.000000000000 0.000000000000 6367.788090000000 -502.892303000000 0.000000000000 4593.000000000000 0.000000000000 -6367.788090000000 0.000000000000 -4072.498050000000 0.000000000000 0.000000000000 4593.000000000000 502.892303000000 4072.498050000000 0.000000000000 0.000000000000 -6367.788090000000 502.892303000000 10319.484399999999 216.334045000000 5728.428710000000 6367.788090000000 0.000000000000 4072.498050000000 216.334045000000 13861.139600000000 -610.934753000000 -502.892303000000 -4072.498050000000 0.000000000000 5728.428710000000 -610.934753000000 4223.301760000000 35 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7182.069820000000 -330.106445000000 0.000000000000 5000.000000000000 0.000000000000 -7182.069820000000 0.000000000000 -4446.147460000000 0.000000000000 0.000000000000 5000.000000000000 330.106445000000 4446.147460000000 0.000000000000 0.000000000000 -7182.069820000000 330.106445000000 12001.589800000000 82.809158300000 6443.807620000000 7182.069820000000 0.000000000000 4446.147460000000 82.809158300000 15863.665000000001 -322.440338000000 -330.106445000000 -4446.147460000000 0.000000000000 6443.807620000000 -322.440338000000 4552.859860000000 35 50 60 3956.000000000000 0.000000000000 0.000000000000 0.000000000000 4558.464840000000 -880.210999000000 0.000000000000 3956.000000000000 0.000000000000 -4558.464840000000 0.000000000000 -3057.626220000000 0.000000000000 0.000000000000 3956.000000000000 880.210999000000 3057.626220000000 0.000000000000 0.000000000000 -4558.464840000000 880.210999000000 6021.543950000000 459.241943000000 3636.260740000000 4558.464840000000 0.000000000000 3057.626220000000 459.241943000000 8282.784180000001 -889.121033000000 -880.210999000000 -3057.626220000000 0.000000000000 3636.260740000000 -889.121033000000 3082.426760000000 35 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7302.612790000000 -1246.657230000000 0.000000000000 5000.000000000000 0.000000000000 -7302.612790000000 0.000000000000 -3608.919920000000 0.000000000000 0.000000000000 5000.000000000000 1246.657230000000 3608.919920000000 0.000000000000 0.000000000000 -7302.612790000000 1246.657230000000 12864.170899999999 661.852112000000 5209.664550000000 7302.612790000000 0.000000000000 3608.919920000000 661.852112000000 15219.273400000000 -1819.861820000000 -1246.657230000000 -3608.919920000000 0.000000000000 5209.664550000000 -1819.861820000000 3515.417970000000 36 47 60 3418.000000000000 0.000000000000 0.000000000000 0.000000000000 4582.744630000000 28.265939700000 0.000000000000 3418.000000000000 0.000000000000 -4582.744630000000 0.000000000000 -1863.463750000000 0.000000000000 0.000000000000 3418.000000000000 -28.265939700000 1863.463750000000 0.000000000000 0.000000000000 -4582.744630000000 -28.265939700000 6808.867190000000 -51.094963100000 2433.279790000000 4582.744630000000 0.000000000000 1863.463750000000 -51.094963100000 7565.405270000000 273.780426000000 28.265939700000 -1863.463750000000 0.000000000000 2433.279790000000 273.780426000000 1503.441040000000 36 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7753.181150000000 253.664032000000 0.000000000000 5000.000000000000 0.000000000000 -7753.181150000000 0.000000000000 -2073.080570000000 0.000000000000 0.000000000000 5000.000000000000 -253.664032000000 2073.080570000000 0.000000000000 0.000000000000 -7753.181150000000 -253.664032000000 13752.334999999999 -86.176109300000 2829.652100000000 7753.181150000000 0.000000000000 2073.080570000000 -86.176109300000 14303.819299999999 826.381287000000 253.664032000000 -2073.080570000000 0.000000000000 2829.652100000000 826.381287000000 1732.126950000000 36 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8318.413090000000 744.971191000000 0.000000000000 5000.000000000000 0.000000000000 -8318.413090000000 0.000000000000 -1825.822750000000 0.000000000000 0.000000000000 5000.000000000000 -744.971191000000 1825.822750000000 0.000000000000 0.000000000000 -8318.413090000000 -744.971191000000 15700.535200000000 -174.571686000000 2502.513670000000 8318.413090000000 0.000000000000 1825.822750000000 -174.571686000000 16127.382799999999 1673.112920000000 744.971191000000 -1825.822750000000 0.000000000000 2502.513670000000 1673.112920000000 1652.306150000000 36 50 60 4663.000000000000 0.000000000000 0.000000000000 0.000000000000 6775.347170000000 65.054107700000 0.000000000000 4663.000000000000 0.000000000000 -6775.347170000000 0.000000000000 -2174.822510000000 0.000000000000 0.000000000000 4663.000000000000 -65.054107700000 2174.822510000000 0.000000000000 0.000000000000 -6775.347170000000 -65.054107700000 10870.412100000000 -45.193065600000 2970.024410000000 6775.347170000000 0.000000000000 2174.822510000000 -45.193065600000 11641.107400000001 382.583252000000 65.054107700000 -2174.822510000000 0.000000000000 2970.024410000000 382.583252000000 1638.161380000000 36 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8411.368160000000 -211.449753000000 0.000000000000 5000.000000000000 0.000000000000 -8411.368160000000 0.000000000000 -1681.671750000000 0.000000000000 0.000000000000 5000.000000000000 211.449753000000 1681.671750000000 0.000000000000 0.000000000000 -8411.368160000000 211.449753000000 16245.362300000001 4.350523470000 2091.560300000000 8411.368160000000 0.000000000000 1681.671750000000 4.350523470000 16792.767599999999 -175.367691000000 -211.449753000000 -1681.671750000000 0.000000000000 2091.560300000000 -175.367691000000 1574.059690000000 37 47 60 2960.000000000000 0.000000000000 0.000000000000 0.000000000000 5292.457030000000 1068.340820000000 0.000000000000 2960.000000000000 0.000000000000 -5292.457030000000 0.000000000000 -1858.530520000000 0.000000000000 0.000000000000 2960.000000000000 -1068.340820000000 1858.530520000000 0.000000000000 0.000000000000 -5292.457030000000 -1068.340820000000 10421.972700000000 -546.703369000000 3154.715820000000 5292.457030000000 0.000000000000 1858.530520000000 -546.703369000000 11166.919900000001 2163.567870000000 1068.340820000000 -1858.530520000000 0.000000000000 3154.715820000000 2163.567870000000 2088.648190000000 37 48 60 4644.000000000000 0.000000000000 0.000000000000 0.000000000000 9252.441409999999 1944.991700000000 0.000000000000 4644.000000000000 0.000000000000 -9252.441409999999 0.000000000000 -2146.241940000000 0.000000000000 0.000000000000 4644.000000000000 -1944.991700000000 2146.241940000000 0.000000000000 0.000000000000 -9252.441409999999 -1944.991700000000 20672.177700000000 -682.505310000000 3630.280030000000 9252.441409999999 0.000000000000 2146.241940000000 -682.505310000000 21142.431600000000 4254.988280000000 1944.991700000000 -2146.241940000000 0.000000000000 3630.280030000000 4254.988280000000 2794.771480000000 37 49 60 4893.000000000000 0.000000000000 0.000000000000 0.000000000000 10110.508800000000 2514.594480000000 0.000000000000 4893.000000000000 0.000000000000 -10110.508800000000 0.000000000000 -1839.078860000000 0.000000000000 0.000000000000 4893.000000000000 -2514.594480000000 1839.078860000000 0.000000000000 0.000000000000 -10110.508800000000 -2514.594480000000 23510.919900000001 -685.163208000000 3100.599120000000 10110.508800000000 0.000000000000 1839.078860000000 -685.163208000000 23324.103500000001 5573.531740000000 2514.594480000000 -1839.078860000000 0.000000000000 3100.599120000000 5573.531740000000 2988.964360000000 37 50 60 3858.000000000000 0.000000000000 0.000000000000 0.000000000000 7558.283690000000 1708.347050000000 0.000000000000 3858.000000000000 0.000000000000 -7558.283690000000 0.000000000000 -2084.870850000000 0.000000000000 0.000000000000 3858.000000000000 -1708.347050000000 2084.870850000000 0.000000000000 0.000000000000 -7558.283690000000 -1708.347050000000 16465.662100000001 -694.034729000000 3638.430180000000 7558.283690000000 0.000000000000 2084.870850000000 -694.034729000000 17056.644499999999 3639.088620000000 1708.347050000000 -2084.870850000000 0.000000000000 3638.430180000000 3639.088620000000 2703.458740000000 37 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10515.138700000000 2243.267090000000 0.000000000000 5000.000000000000 0.000000000000 -10515.138700000000 0.000000000000 -2103.949460000000 0.000000000000 0.000000000000 5000.000000000000 -2243.267090000000 2103.949460000000 0.000000000000 0.000000000000 -10515.138700000000 -2243.267090000000 24772.187500000000 -664.468506000000 3503.016600000000 10515.138700000000 0.000000000000 2103.949460000000 -664.468506000000 25132.210899999998 5080.986330000000 2243.267090000000 -2103.949460000000 0.000000000000 3503.016600000000 5080.986330000000 3284.158940000000 38 49 60 1532.000000000000 0.000000000000 0.000000000000 0.000000000000 3959.525390000000 1472.574710000000 0.000000000000 1532.000000000000 0.000000000000 -3959.525390000000 0.000000000000 362.584900000000 0.000000000000 0.000000000000 1532.000000000000 -1472.574710000000 -362.584900000000 0.000000000000 0.000000000000 -3959.525390000000 -1472.574710000000 12181.674800000001 511.622498000000 -1307.891850000000 3959.525390000000 0.000000000000 -362.584900000000 511.622498000000 11101.120100000000 3975.310790000000 1472.574710000000 362.584900000000 0.000000000000 -1307.891850000000 3975.310790000000 1962.929440000000 38 52 60 2020.000000000000 0.000000000000 0.000000000000 0.000000000000 5025.845210000000 1734.793090000000 0.000000000000 2020.000000000000 0.000000000000 -5025.845210000000 0.000000000000 118.812057000000 0.000000000000 0.000000000000 2020.000000000000 -1734.793090000000 -118.812057000000 0.000000000000 0.000000000000 -5025.845210000000 -1734.793090000000 14593.992200000001 252.794724000000 -757.410950000000 5025.845210000000 0.000000000000 -118.812057000000 252.794724000000 13570.819299999999 4459.299320000000 1734.793090000000 118.812057000000 0.000000000000 -757.410950000000 4459.299320000000 2273.676760000000 38 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14476.795899999999 5295.410640000000 0.000000000000 5000.000000000000 0.000000000000 -14476.795899999999 0.000000000000 3096.660160000000 0.000000000000 0.000000000000 5000.000000000000 -5295.410640000000 -3096.660160000000 0.000000000000 0.000000000000 -14476.795899999999 -5295.410640000000 49418.906300000002 3908.988530000000 -10281.810500000000 14476.795899999999 0.000000000000 -3096.660160000000 3908.988530000000 46776.109400000001 15969.388700000000 5295.410640000000 3096.660160000000 0.000000000000 -10281.810500000000 15969.388700000000 9461.292970000000 38 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9139.227540000000 706.002991000000 0.000000000000 5000.000000000000 0.000000000000 -9139.227540000000 0.000000000000 3643.843020000000 0.000000000000 0.000000000000 5000.000000000000 -706.002991000000 -3643.843020000000 0.000000000000 0.000000000000 -9139.227540000000 -706.002991000000 20124.871100000000 728.109924000000 -7074.606450000000 9139.227540000000 0.000000000000 -3643.843020000000 728.109924000000 22687.224600000001 2504.201660000000 706.002991000000 3643.843020000000 0.000000000000 -7074.606450000000 2504.201660000000 3968.537350000000 39 47 60 2359.000000000000 0.000000000000 0.000000000000 0.000000000000 5616.636230000000 2304.600100000000 0.000000000000 2359.000000000000 0.000000000000 -5616.636230000000 0.000000000000 -1475.728150000000 0.000000000000 0.000000000000 2359.000000000000 -2304.600100000000 1475.728150000000 0.000000000000 0.000000000000 -5616.636230000000 -2304.600100000000 15967.594700000000 -1314.908080000000 3293.125000000000 5616.636230000000 0.000000000000 1475.728150000000 -1314.908080000000 14862.030300000000 5618.151860000000 2304.600100000000 -1475.728150000000 0.000000000000 3293.125000000000 5618.151860000000 3687.373290000000 39 48 60 3293.000000000000 0.000000000000 0.000000000000 0.000000000000 8187.653810000000 3247.681880000000 0.000000000000 3293.000000000000 0.000000000000 -8187.653810000000 0.000000000000 -1481.384400000000 0.000000000000 0.000000000000 3293.000000000000 -3247.681880000000 1481.384400000000 0.000000000000 0.000000000000 -8187.653810000000 -3247.681880000000 24124.085899999998 -1289.556270000000 3255.019290000000 8187.653810000000 0.000000000000 1481.384400000000 -1289.556270000000 22097.785199999998 8239.276370000000 3247.681880000000 -1481.384400000000 0.000000000000 3255.019290000000 8239.276370000000 4748.930660000000 39 49 60 3888.000000000000 0.000000000000 0.000000000000 0.000000000000 10601.034200000000 3990.018070000000 0.000000000000 3888.000000000000 0.000000000000 -10601.034200000000 0.000000000000 -453.806824000000 0.000000000000 0.000000000000 3888.000000000000 -3990.018070000000 453.806824000000 0.000000000000 0.000000000000 -10601.034200000000 -3990.018070000000 33967.230499999998 -272.998291000000 332.140564000000 10601.034200000000 0.000000000000 453.806824000000 -272.998291000000 30956.632799999999 11047.711900000000 3990.018070000000 -453.806824000000 0.000000000000 332.140564000000 11047.711900000000 5490.329590000000 39 50 60 3227.000000000000 0.000000000000 0.000000000000 0.000000000000 8187.933110000000 3091.739500000000 0.000000000000 3227.000000000000 0.000000000000 -8187.933110000000 0.000000000000 -1419.033940000000 0.000000000000 0.000000000000 3227.000000000000 -3091.739500000000 1419.033940000000 0.000000000000 0.000000000000 -8187.933110000000 -3091.739500000000 24383.724600000001 -1218.937010000000 3103.240480000000 8187.933110000000 0.000000000000 1419.033940000000 -1218.937010000000 22552.941400000000 7997.405760000000 3091.739500000000 -1419.033940000000 0.000000000000 3103.240480000000 7997.405760000000 4420.224120000000 39 52 60 4291.000000000000 0.000000000000 0.000000000000 0.000000000000 11063.280300000000 4023.468750000000 0.000000000000 4291.000000000000 0.000000000000 -11063.280300000000 0.000000000000 -1577.960820000000 0.000000000000 0.000000000000 4291.000000000000 -4023.468750000000 1577.960820000000 0.000000000000 0.000000000000 -11063.280300000000 -4023.468750000000 33263.554700000001 -1255.276980000000 3334.395750000000 11063.280300000000 0.000000000000 1577.960820000000 -1255.276980000000 30815.441400000000 10547.221700000000 4023.468750000000 -1577.960820000000 0.000000000000 3334.395750000000 10547.221700000000 5653.695800000000 39 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14048.389600000000 5142.410160000000 0.000000000000 5000.000000000000 0.000000000000 -14048.389600000000 0.000000000000 264.009705000000 0.000000000000 0.000000000000 5000.000000000000 -5142.410160000000 -264.009705000000 0.000000000000 0.000000000000 -14048.389600000000 -5142.410160000000 46078.582000000002 642.078369000000 -1860.118770000000 14048.389600000000 0.000000000000 -264.009705000000 642.078369000000 42118.671900000001 14709.743200000001 5142.410160000000 264.009705000000 0.000000000000 -1860.118770000000 14709.743200000001 7217.589360000000 39 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11601.377899999999 2454.646970000000 0.000000000000 5000.000000000000 0.000000000000 -11601.377899999999 0.000000000000 2611.016110000000 0.000000000000 0.000000000000 5000.000000000000 -2454.646970000000 -2611.016110000000 0.000000000000 0.000000000000 -11601.377899999999 -2454.646970000000 32887.726600000002 1850.039790000000 -6754.980470000000 11601.377899999999 0.000000000000 -2611.016110000000 1850.039790000000 31885.687500000000 7895.358400000000 2454.646970000000 2611.016110000000 0.000000000000 -6754.980470000000 7895.358400000000 5036.150880000000 39 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9011.489260000000 405.835052000000 0.000000000000 5000.000000000000 0.000000000000 -9011.489260000000 0.000000000000 1996.527590000000 0.000000000000 0.000000000000 5000.000000000000 -405.835052000000 -1996.527590000000 0.000000000000 0.000000000000 -9011.489260000000 -405.835052000000 18532.074199999999 439.019806000000 -4025.825200000000 9011.489260000000 0.000000000000 -1996.527590000000 439.019806000000 19120.349600000001 1762.814940000000 405.835052000000 1996.527590000000 0.000000000000 -4025.825200000000 1762.814940000000 2276.329100000000 39 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9171.304690000001 18.128646900000 0.000000000000 5000.000000000000 0.000000000000 -9171.304690000001 0.000000000000 1426.059450000000 0.000000000000 0.000000000000 5000.000000000000 -18.128646900000 -1426.059450000000 0.000000000000 0.000000000000 -9171.304690000001 -18.128646900000 19040.337899999999 -44.090049700000 -2568.701660000000 9171.304690000001 0.000000000000 -1426.059450000000 -44.090049700000 19733.785199999998 692.917358000000 18.128646900000 1426.059450000000 0.000000000000 -2568.701660000000 692.917358000000 1247.065310000000 40 44 60 4584.000000000000 0.000000000000 0.000000000000 0.000000000000 14858.837900000000 1033.207640000000 0.000000000000 4584.000000000000 0.000000000000 -14858.837900000000 0.000000000000 4534.205080000000 0.000000000000 0.000000000000 4584.000000000000 -1033.207640000000 -4534.205080000000 0.000000000000 0.000000000000 -14858.837900000000 -1033.207640000000 49155.503900000003 1326.945070000000 -14975.254900000000 14858.837900000000 0.000000000000 -4534.205080000000 1326.945070000000 53828.804700000001 3505.440430000000 1033.207640000000 4534.205080000000 0.000000000000 -14975.254900000000 3505.440430000000 6175.342290000000 40 45 60 3857.000000000000 0.000000000000 0.000000000000 0.000000000000 12624.163100000000 713.503479000000 0.000000000000 3857.000000000000 0.000000000000 -12624.163100000000 0.000000000000 4192.303220000000 0.000000000000 0.000000000000 3857.000000000000 -713.503479000000 -4192.303220000000 0.000000000000 0.000000000000 -12624.163100000000 -713.503479000000 41935.398399999998 952.973877000000 -13755.059600000001 12624.163100000000 0.000000000000 -4192.303220000000 952.973877000000 46382.539100000002 2452.227780000000 713.503479000000 4192.303220000000 0.000000000000 -13755.059600000001 2452.227780000000 5467.720700000000 40 46 60 3156.000000000000 0.000000000000 0.000000000000 0.000000000000 10316.409200000000 574.903870000000 0.000000000000 3156.000000000000 0.000000000000 -10316.409200000000 0.000000000000 3787.586670000000 0.000000000000 0.000000000000 3156.000000000000 -574.903870000000 -3787.586670000000 0.000000000000 0.000000000000 -10316.409200000000 -574.903870000000 34207.238299999997 775.302795000000 -12403.055700000001 10316.409200000000 0.000000000000 -3787.586670000000 775.302795000000 38501.058599999997 1989.498410000000 574.903870000000 3787.586670000000 0.000000000000 -12403.055700000001 1989.498410000000 5062.601560000000 41 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15472.128900000000 -139.109009000000 0.000000000000 5000.000000000000 0.000000000000 -15472.128900000000 0.000000000000 5433.523440000000 0.000000000000 0.000000000000 5000.000000000000 139.109009000000 -5433.523440000000 0.000000000000 0.000000000000 -15472.128900000000 139.109009000000 48730.316400000003 -146.936783000000 -16707.248000000000 15472.128900000000 0.000000000000 -5433.523440000000 -146.936783000000 54347.031300000002 -158.195923000000 -139.109009000000 5433.523440000000 0.000000000000 -16707.248000000000 -158.195923000000 6469.047360000000 42 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13237.516600000001 -156.324631000000 0.000000000000 5000.000000000000 0.000000000000 -13237.516600000001 0.000000000000 4131.288570000000 0.000000000000 0.000000000000 5000.000000000000 156.324631000000 -4131.288570000000 0.000000000000 0.000000000000 -13237.516600000001 156.324631000000 35699.421900000001 -151.992737000000 -10805.019500000000 13237.516600000001 0.000000000000 -4131.288570000000 -151.992737000000 39017.890599999999 -234.051819000000 -156.324631000000 4131.288570000000 0.000000000000 -10805.019500000000 -234.051819000000 4029.607420000000 43 47 60 1174.000000000000 0.000000000000 0.000000000000 0.000000000000 2326.324710000000 20.256090200000 0.000000000000 1174.000000000000 0.000000000000 -2326.324710000000 0.000000000000 1408.702150000000 0.000000000000 0.000000000000 1174.000000000000 -20.256090200000 -1408.702150000000 0.000000000000 0.000000000000 -2326.324710000000 -20.256090200000 4695.565920000000 26.873457000000 -2787.025630000000 2326.324710000000 0.000000000000 -1408.702150000000 26.873457000000 6350.792970000000 55.769615200000 20.256090200000 1408.702150000000 0.000000000000 -2787.025630000000 55.769615200000 1793.007810000000 44 47 60 2449.000000000000 0.000000000000 0.000000000000 0.000000000000 4502.600590000000 372.912842000000 0.000000000000 2449.000000000000 0.000000000000 -4502.600590000000 0.000000000000 2101.051030000000 0.000000000000 0.000000000000 2449.000000000000 -372.912842000000 -2101.051030000000 0.000000000000 0.000000000000 -4502.600590000000 -372.912842000000 8539.954100000001 325.829315000000 -3840.789790000000 4502.600590000000 0.000000000000 -2101.051030000000 325.829315000000 10234.625000000000 698.967651000000 372.912842000000 2101.051030000000 0.000000000000 -3840.789790000000 698.967651000000 2146.182130000000 44 48 60 1138.000000000000 0.000000000000 0.000000000000 0.000000000000 2086.855960000000 62.576831800000 0.000000000000 1138.000000000000 0.000000000000 -2086.855960000000 0.000000000000 1212.345090000000 0.000000000000 0.000000000000 1138.000000000000 -62.576831800000 -1212.345090000000 0.000000000000 0.000000000000 -2086.855960000000 -62.576831800000 3911.845950000000 71.053131100000 -2221.517090000000 2086.855960000000 0.000000000000 -1212.345090000000 71.053131100000 5133.211910000000 109.644150000000 62.576831800000 1212.345090000000 0.000000000000 -2221.517090000000 109.644150000000 1381.100830000000 45 48 60 3860.000000000000 0.000000000000 0.000000000000 0.000000000000 6264.568360000000 251.186249000000 0.000000000000 3860.000000000000 0.000000000000 -6264.568360000000 0.000000000000 3579.833980000000 0.000000000000 0.000000000000 3860.000000000000 -251.186249000000 -3579.833980000000 0.000000000000 0.000000000000 -6264.568360000000 -251.186249000000 10454.127899999999 296.545715000000 -5772.676270000000 6264.568360000000 0.000000000000 -3579.833980000000 296.545715000000 13716.891600000001 410.456543000000 251.186249000000 3579.833980000000 0.000000000000 -5772.676270000000 410.456543000000 3748.633790000000 45 49 60 2583.000000000000 0.000000000000 0.000000000000 0.000000000000 4160.963380000000 225.061050000000 0.000000000000 2583.000000000000 0.000000000000 -4160.963380000000 0.000000000000 2713.837890000000 0.000000000000 0.000000000000 2583.000000000000 -225.061050000000 -2713.837890000000 0.000000000000 0.000000000000 -4160.963380000000 -225.061050000000 6843.886230000000 263.267334000000 -4363.547360000000 4160.963380000000 0.000000000000 -2713.837890000000 263.267334000000 9625.518550000001 360.503540000000 225.061050000000 2713.837890000000 0.000000000000 -4363.547360000000 360.503540000000 3036.770510000000 45 50 60 2090.000000000000 0.000000000000 0.000000000000 0.000000000000 3476.030520000000 -336.850708000000 0.000000000000 2090.000000000000 0.000000000000 -3476.030520000000 0.000000000000 1762.638430000000 0.000000000000 0.000000000000 2090.000000000000 336.850708000000 -1762.638430000000 0.000000000000 0.000000000000 -3476.030520000000 336.850708000000 5911.654790000000 -251.484177000000 -2901.477780000000 3476.030520000000 0.000000000000 -1762.638430000000 -251.484177000000 7402.273930000000 -561.762085000000 -336.850708000000 1762.638430000000 0.000000000000 -2901.477780000000 -561.762085000000 1695.918820000000 45 51 60 1600.000000000000 0.000000000000 0.000000000000 0.000000000000 2648.211180000000 -311.025604000000 0.000000000000 1600.000000000000 0.000000000000 -2648.211180000000 0.000000000000 1259.900880000000 0.000000000000 0.000000000000 1600.000000000000 311.025604000000 -1259.900880000000 0.000000000000 0.000000000000 -2648.211180000000 311.025604000000 4502.574710000000 -240.395798000000 -2053.067140000000 2648.211180000000 0.000000000000 -1259.900880000000 -240.395798000000 5513.108400000000 -507.675385000000 -311.025604000000 1259.900880000000 0.000000000000 -2053.067140000000 -507.675385000000 1189.912600000000 45 52 60 2295.000000000000 0.000000000000 0.000000000000 0.000000000000 3729.704100000000 -350.468079000000 0.000000000000 2295.000000000000 0.000000000000 -3729.704100000000 0.000000000000 2084.597170000000 0.000000000000 0.000000000000 2295.000000000000 350.468079000000 -2084.597170000000 0.000000000000 0.000000000000 -3729.704100000000 350.468079000000 6218.199220000000 -280.593689000000 -3362.488770000000 3729.704100000000 0.000000000000 -2084.597170000000 -280.593689000000 8093.064940000000 -561.062988000000 -350.468079000000 2084.597170000000 0.000000000000 -3362.488770000000 -561.062988000000 2102.931640000000 46 53 60 3078.000000000000 0.000000000000 0.000000000000 0.000000000000 4794.840330000000 -124.774597000000 0.000000000000 3078.000000000000 0.000000000000 -4794.840330000000 0.000000000000 2482.086180000000 0.000000000000 0.000000000000 3078.000000000000 124.774597000000 -2482.086180000000 0.000000000000 0.000000000000 -4794.840330000000 124.774597000000 7642.817870000000 -76.768470800000 -3881.089840000000 4794.840330000000 0.000000000000 -2482.086180000000 -76.768470800000 9696.884770000001 -129.626587000000 -124.774597000000 2482.086180000000 0.000000000000 -3881.089840000000 -129.626587000000 2271.493410000000 47 54 60 1904.000000000000 0.000000000000 0.000000000000 0.000000000000 3156.125730000000 -244.878098000000 0.000000000000 1904.000000000000 0.000000000000 -3156.125730000000 0.000000000000 1930.573970000000 0.000000000000 0.000000000000 1904.000000000000 244.878098000000 -1930.573970000000 0.000000000000 0.000000000000 -3156.125730000000 244.878098000000 5440.260740000000 -222.864655000000 -3279.250730000000 3156.125730000000 0.000000000000 -1930.573970000000 -222.864655000000 7383.375000000000 -358.309326000000 -244.878098000000 1930.573970000000 0.000000000000 -3279.250730000000 -358.309326000000 2177.021240000000 48 58 60 1085.000000000000 0.000000000000 0.000000000000 0.000000000000 2157.739500000000 -560.816895000000 0.000000000000 1085.000000000000 0.000000000000 -2157.739500000000 0.000000000000 1206.246460000000 0.000000000000 0.000000000000 1085.000000000000 560.816895000000 -1206.246460000000 0.000000000000 0.000000000000 -2157.739500000000 560.816895000000 4811.156250000000 -652.878967000000 -2523.486080000000 2157.739500000000 0.000000000000 -1206.246460000000 -652.878967000000 5907.050290000000 -1155.793950000000 -560.816895000000 1206.246460000000 0.000000000000 -2523.486080000000 -1155.793950000000 1754.992920000000 48 59 60 1614.000000000000 0.000000000000 0.000000000000 0.000000000000 2484.918460000000 -820.129700000000 0.000000000000 1614.000000000000 0.000000000000 -2484.918460000000 0.000000000000 1201.071410000000 0.000000000000 0.000000000000 1614.000000000000 820.129700000000 -1201.071410000000 0.000000000000 0.000000000000 -2484.918460000000 820.129700000000 4829.970210000000 -737.365906000000 -2270.644290000000 2484.918460000000 0.000000000000 -1201.071410000000 -737.365906000000 5598.563960000000 -1419.646970000000 -820.129700000000 1201.071410000000 0.000000000000 -2270.644290000000 -1419.646970000000 1729.606080000000 49 55 60 1422.000000000000 0.000000000000 0.000000000000 0.000000000000 2993.353030000000 -587.630798000000 0.000000000000 1422.000000000000 0.000000000000 -2993.353030000000 0.000000000000 1515.049070000000 0.000000000000 0.000000000000 1422.000000000000 587.630798000000 -1515.049070000000 0.000000000000 0.000000000000 -2993.353030000000 587.630798000000 6709.854490000000 -639.572815000000 -3209.125490000000 2993.353030000000 0.000000000000 -1515.049070000000 -639.572815000000 7988.504880000000 -1299.128780000000 -587.630798000000 1515.049070000000 0.000000000000 -3209.125490000000 -1299.128780000000 1981.698240000000 49 58 60 1356.000000000000 0.000000000000 0.000000000000 0.000000000000 2649.945310000000 -670.432190000000 0.000000000000 1356.000000000000 0.000000000000 -2649.945310000000 0.000000000000 1212.894170000000 0.000000000000 0.000000000000 1356.000000000000 670.432190000000 -1212.894170000000 0.000000000000 0.000000000000 -2649.945310000000 670.432190000000 5783.694820000000 -611.996338000000 -2522.998540000000 2649.945310000000 0.000000000000 -1212.894170000000 -611.996338000000 6615.897460000000 -1330.108520000000 -670.432190000000 1212.894170000000 0.000000000000 -2522.998540000000 -1330.108520000000 1545.057250000000 49 59 60 1539.000000000000 0.000000000000 0.000000000000 0.000000000000 2489.652590000000 -846.146729000000 0.000000000000 1539.000000000000 0.000000000000 -2489.652590000000 0.000000000000 1048.081050000000 0.000000000000 0.000000000000 1539.000000000000 846.146729000000 -1048.081050000000 0.000000000000 0.000000000000 -2489.652590000000 846.146729000000 5141.065430000000 -662.381287000000 -2108.021240000000 2489.652590000000 0.000000000000 -1048.081050000000 -662.381287000000 5635.909180000000 -1493.333130000000 -846.146729000000 1048.081050000000 0.000000000000 -2108.021240000000 -1493.333130000000 1526.146970000000 50 59 60 1672.000000000000 0.000000000000 0.000000000000 0.000000000000 2191.918210000000 -412.595795000000 0.000000000000 1672.000000000000 0.000000000000 -2191.918210000000 0.000000000000 920.340515000000 0.000000000000 0.000000000000 1672.000000000000 412.595795000000 -920.340515000000 0.000000000000 0.000000000000 -2191.918210000000 412.595795000000 3396.675050000000 -195.732071000000 -1463.738160000000 2191.918210000000 0.000000000000 -920.340515000000 -195.732071000000 3959.156980000000 -491.211121000000 -412.595795000000 920.340515000000 0.000000000000 -1463.738160000000 -491.211121000000 813.556946000000 51 54 60 633.000000000000 0.000000000000 0.000000000000 0.000000000000 609.678284000000 -10.995534900000 0.000000000000 633.000000000000 0.000000000000 -609.678284000000 0.000000000000 357.115875000000 0.000000000000 0.000000000000 633.000000000000 10.995534900000 -357.115875000000 0.000000000000 0.000000000000 -609.678284000000 10.995534900000 628.184265000000 2.969370130000 -350.161438000000 609.678284000000 0.000000000000 -357.115875000000 2.969370130000 804.036804000000 5.065117360000 -10.995534900000 357.115875000000 0.000000000000 -350.161438000000 5.065117360000 235.191330000000 51 59 60 458.000000000000 0.000000000000 0.000000000000 0.000000000000 370.494904000000 -120.563637000000 0.000000000000 458.000000000000 0.000000000000 -370.494904000000 0.000000000000 150.327881000000 0.000000000000 0.000000000000 458.000000000000 120.563637000000 -150.327881000000 0.000000000000 0.000000000000 -370.494904000000 120.563637000000 334.816650000000 -36.958282500000 -122.230774000000 370.494904000000 0.000000000000 -150.327881000000 -36.958282500000 355.833069000000 -97.170730600000 -120.563637000000 150.327881000000 0.000000000000 -122.230774000000 -97.170730600000 90.262962300000 52 55 60 1130.000000000000 0.000000000000 0.000000000000 0.000000000000 1951.959960000000 -620.454773000000 0.000000000000 1130.000000000000 0.000000000000 -1951.959960000000 0.000000000000 1561.005370000000 0.000000000000 0.000000000000 1130.000000000000 620.454773000000 -1561.005370000000 0.000000000000 0.000000000000 -1951.959960000000 620.454773000000 3943.389160000000 -852.075806000000 -2702.637940000000 1951.959960000000 0.000000000000 -1561.005370000000 -852.075806000000 5586.089360000000 -1134.723020000000 -620.454773000000 1561.005370000000 0.000000000000 -2702.637940000000 -1134.723020000000 2687.517820000000 52 58 60 778.000000000000 0.000000000000 0.000000000000 0.000000000000 1089.097290000000 -152.781296000000 0.000000000000 778.000000000000 0.000000000000 -1089.097290000000 0.000000000000 788.955627000000 0.000000000000 0.000000000000 778.000000000000 152.781296000000 -788.955627000000 0.000000000000 0.000000000000 -1089.097290000000 152.781296000000 1714.286250000000 -147.720291000000 -1215.331910000000 1089.097290000000 0.000000000000 -788.955627000000 -147.720291000000 2555.586910000000 -209.039474000000 -152.781296000000 788.955627000000 0.000000000000 -1215.331910000000 -209.039474000000 946.100098000000 52 59 60 2020.000000000000 0.000000000000 0.000000000000 0.000000000000 2510.507080000000 -431.511993000000 0.000000000000 2020.000000000000 0.000000000000 -2510.507080000000 0.000000000000 1646.493160000000 0.000000000000 0.000000000000 2020.000000000000 431.511993000000 -1646.493160000000 0.000000000000 0.000000000000 -2510.507080000000 431.511993000000 3665.762450000000 -363.948761000000 -2433.671390000000 2510.507080000000 0.000000000000 -1646.493160000000 -363.948761000000 5266.558590000000 -535.063416000000 -431.511993000000 1646.493160000000 0.000000000000 -2433.671390000000 -535.063416000000 1920.595210000000 53 56 60 2823.000000000000 0.000000000000 0.000000000000 0.000000000000 5615.717770000000 -1632.097660000000 0.000000000000 2823.000000000000 0.000000000000 -5615.717770000000 0.000000000000 3031.737300000000 0.000000000000 0.000000000000 2823.000000000000 1632.097660000000 -3031.737300000000 0.000000000000 0.000000000000 -5615.717770000000 1632.097660000000 13016.615200000000 -1697.267210000000 -5929.271480000000 5615.717770000000 0.000000000000 -3031.737300000000 -1697.267210000000 15292.540000000001 -3235.103520000000 -1632.097660000000 3031.737300000000 0.000000000000 -5929.271480000000 -3235.103520000000 4473.975590000000 53 57 60 1462.000000000000 0.000000000000 0.000000000000 0.000000000000 2806.560060000000 -1045.480830000000 0.000000000000 1462.000000000000 0.000000000000 -2806.560060000000 0.000000000000 1509.826900000000 0.000000000000 0.000000000000 1462.000000000000 1045.480830000000 -1509.826900000000 0.000000000000 0.000000000000 -2806.560060000000 1045.480830000000 6362.947750000000 -1068.883910000000 -2900.864990000000 2806.560060000000 0.000000000000 -1509.826900000000 -1068.883910000000 7228.290530000000 -2027.556640000000 -1045.480830000000 1509.826900000000 0.000000000000 -2900.864990000000 -2027.556640000000 2404.022220000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-home_at-home_at_scan1_2013_jan_1/gt.info ================================================ 0 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12744.660200000000 -1672.731570000000 0.000000000000 5000.000000000000 0.000000000000 -12744.660200000000 0.000000000000 -5858.469730000000 0.000000000000 0.000000000000 5000.000000000000 1672.731570000000 5858.469730000000 0.000000000000 0.000000000000 -12744.660200000000 1672.731570000000 33810.699200000003 2054.622310000000 15214.499000000000 12744.660200000000 0.000000000000 5858.469730000000 2054.622310000000 40308.414100000002 -4248.522460000000 -1672.731570000000 -5858.469730000000 0.000000000000 15214.499000000000 -4248.522460000000 7972.482910000000 0 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11775.328100000001 -1012.331420000000 0.000000000000 5000.000000000000 0.000000000000 -11775.328100000001 0.000000000000 -3992.200930000000 0.000000000000 0.000000000000 5000.000000000000 1012.331420000000 3992.200930000000 0.000000000000 0.000000000000 -11775.328100000001 1012.331420000000 29121.611300000000 1300.829960000000 9872.862300000001 11775.328100000001 0.000000000000 3992.200930000000 1300.829960000000 32766.716799999998 -2424.805180000000 -1012.331420000000 -3992.200930000000 0.000000000000 9872.862300000001 -2424.805180000000 5002.444820000000 0 33 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10770.032200000000 -1061.821780000000 0.000000000000 5000.000000000000 0.000000000000 -10770.032200000000 0.000000000000 -2316.837650000000 0.000000000000 0.000000000000 5000.000000000000 1061.821780000000 2316.837650000000 0.000000000000 0.000000000000 -10770.032200000000 1061.821780000000 24489.468799999999 911.144287000000 5323.265140000000 10770.032200000000 0.000000000000 2316.837650000000 911.144287000000 25788.863300000001 -2317.833010000000 -1061.821780000000 -2316.837650000000 0.000000000000 5323.265140000000 -2317.833010000000 2844.026120000000 0 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11438.655300000000 328.855835000000 0.000000000000 5000.000000000000 0.000000000000 -11438.655300000000 0.000000000000 1113.335690000000 0.000000000000 0.000000000000 5000.000000000000 -328.855835000000 -1113.335690000000 0.000000000000 0.000000000000 -11438.655300000000 -328.855835000000 27409.847699999998 143.385086000000 -2757.857420000000 11438.655300000000 0.000000000000 -1113.335690000000 143.385086000000 28871.722699999998 1071.766850000000 328.855835000000 1113.335690000000 0.000000000000 -2757.857420000000 1071.766850000000 2511.013670000000 0 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13271.854499999999 1663.855100000000 0.000000000000 5000.000000000000 0.000000000000 -13271.854499999999 0.000000000000 2154.753660000000 0.000000000000 0.000000000000 5000.000000000000 -1663.855100000000 -2154.753660000000 0.000000000000 0.000000000000 -13271.854499999999 -1663.855100000000 36472.261700000003 903.943481000000 -6232.939450000000 13271.854499999999 0.000000000000 -2154.753660000000 903.943481000000 38767.566400000003 4515.642090000000 1663.855100000000 2154.753660000000 0.000000000000 -6232.939450000000 4515.642090000000 3773.902590000000 0 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11429.252000000000 204.450836000000 0.000000000000 5000.000000000000 0.000000000000 -11429.252000000000 0.000000000000 251.712112000000 0.000000000000 0.000000000000 5000.000000000000 -204.450836000000 -251.712112000000 0.000000000000 0.000000000000 -11429.252000000000 -204.450836000000 28030.330099999999 436.683624000000 -1333.912600000000 11429.252000000000 0.000000000000 -251.712112000000 436.683624000000 28603.496100000000 1030.007080000000 204.450836000000 251.712112000000 0.000000000000 -1333.912600000000 1030.007080000000 2016.653320000000 0 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11889.170899999999 1037.651980000000 0.000000000000 5000.000000000000 0.000000000000 -11889.170899999999 0.000000000000 1132.849610000000 0.000000000000 0.000000000000 5000.000000000000 -1037.651980000000 -1132.849610000000 0.000000000000 0.000000000000 -11889.170899999999 -1037.651980000000 29867.320299999999 474.465454000000 -3420.111570000000 11889.170899999999 0.000000000000 -1132.849610000000 474.465454000000 31281.636699999999 2768.533200000000 1037.651980000000 1132.849610000000 0.000000000000 -3420.111570000000 2768.533200000000 2379.012940000000 0 38 60 4320.000000000000 0.000000000000 0.000000000000 0.000000000000 8762.178710000000 643.000549000000 0.000000000000 4320.000000000000 0.000000000000 -8762.178710000000 0.000000000000 762.270996000000 0.000000000000 0.000000000000 4320.000000000000 -643.000549000000 -762.270996000000 0.000000000000 0.000000000000 -8762.178710000000 -643.000549000000 19040.791000000001 464.288635000000 -2212.892580000000 8762.178710000000 0.000000000000 -762.270996000000 464.288635000000 20148.181600000000 1695.650020000000 643.000549000000 762.270996000000 0.000000000000 -2212.892580000000 1695.650020000000 1822.656250000000 0 41 60 3335.000000000000 0.000000000000 0.000000000000 0.000000000000 6162.239260000000 -1067.584720000000 0.000000000000 3335.000000000000 0.000000000000 -6162.239260000000 0.000000000000 -1994.760990000000 0.000000000000 0.000000000000 3335.000000000000 1067.584720000000 1994.760990000000 0.000000000000 0.000000000000 -6162.239260000000 1067.584720000000 12391.444299999999 975.286865000000 3753.245850000000 6162.239260000000 0.000000000000 1994.760990000000 975.286865000000 13462.884800000000 -2011.357790000000 -1067.584720000000 -1994.760990000000 0.000000000000 3753.245850000000 -2011.357790000000 2513.475830000000 0 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9740.734380000000 -2718.122070000000 0.000000000000 5000.000000000000 0.000000000000 -9740.734380000000 0.000000000000 -5082.485840000000 0.000000000000 0.000000000000 5000.000000000000 2718.122070000000 5082.485840000000 0.000000000000 0.000000000000 -9740.734380000000 2718.122070000000 20912.507799999999 2815.725340000000 10100.470700000000 9740.734380000000 0.000000000000 5082.485840000000 2815.725340000000 24932.902300000002 -5252.835450000000 -2718.122070000000 -5082.485840000000 0.000000000000 10100.470700000000 -5252.835450000000 7256.946290000000 0 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10506.489299999999 -2018.042480000000 0.000000000000 5000.000000000000 0.000000000000 -10506.489299999999 0.000000000000 -4253.328130000000 0.000000000000 0.000000000000 5000.000000000000 2018.042480000000 4253.328130000000 0.000000000000 0.000000000000 -10506.489299999999 2018.042480000000 23893.181600000000 1980.725340000000 9281.080080000000 10506.489299999999 0.000000000000 4253.328130000000 1980.725340000000 27261.871100000000 -4231.816890000000 -2018.042480000000 -4253.328130000000 0.000000000000 9281.080080000000 -4231.816890000000 5777.123540000000 0 49 60 3517.000000000000 0.000000000000 0.000000000000 0.000000000000 10021.001000000000 577.604553000000 0.000000000000 3517.000000000000 0.000000000000 -10021.001000000000 0.000000000000 1777.180790000000 0.000000000000 0.000000000000 3517.000000000000 -577.604553000000 -1777.180790000000 0.000000000000 0.000000000000 -10021.001000000000 -577.604553000000 29552.335899999998 234.760651000000 -5244.482910000000 10021.001000000000 0.000000000000 -1777.180790000000 234.760651000000 31282.312500000000 1482.203130000000 577.604553000000 1777.180790000000 0.000000000000 -5244.482910000000 1482.203130000000 2541.072270000000 0 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14517.904300000000 1286.432500000000 0.000000000000 5000.000000000000 0.000000000000 -14517.904300000000 0.000000000000 4353.865230000000 0.000000000000 0.000000000000 5000.000000000000 -1286.432500000000 -4353.865230000000 0.000000000000 0.000000000000 -14517.904300000000 -1286.432500000000 43522.773399999998 1236.970210000000 -12421.111300000000 14517.904300000000 0.000000000000 -4353.865230000000 1236.970210000000 46957.335899999998 3467.930180000000 1286.432500000000 4353.865230000000 0.000000000000 -12421.111300000000 3467.930180000000 4953.535160000000 0 51 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15735.231400000001 3383.734130000000 0.000000000000 5000.000000000000 0.000000000000 -15735.231400000001 0.000000000000 5583.377930000000 0.000000000000 0.000000000000 5000.000000000000 -3383.734130000000 -5583.377930000000 0.000000000000 0.000000000000 -15735.231400000001 -3383.734130000000 53188.925799999997 4306.197750000000 -17492.716799999998 15735.231400000001 0.000000000000 -5583.377930000000 4306.197750000000 56628.195299999999 10585.163100000000 3383.734130000000 5583.377930000000 0.000000000000 -17492.716799999998 10585.163100000000 10194.899400000000 1 3 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11630.451200000000 -1080.183840000000 0.000000000000 5000.000000000000 0.000000000000 -11630.451200000000 0.000000000000 -2249.233150000000 0.000000000000 0.000000000000 5000.000000000000 1080.183840000000 2249.233150000000 0.000000000000 0.000000000000 -11630.451200000000 1080.183840000000 28835.919900000001 562.147705000000 5434.411130000000 11630.451200000000 0.000000000000 2249.233150000000 562.147705000000 29784.197300000000 -2371.095460000000 -1080.183840000000 -2249.233150000000 0.000000000000 5434.411130000000 -2371.095460000000 2137.874270000000 1 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12289.525400000000 -1685.119140000000 0.000000000000 5000.000000000000 0.000000000000 -12289.525400000000 0.000000000000 -4165.743160000000 0.000000000000 0.000000000000 5000.000000000000 1685.119140000000 4165.743160000000 0.000000000000 0.000000000000 -12289.525400000000 1685.119140000000 32163.843799999999 1865.262820000000 10603.365200000000 12289.525400000000 0.000000000000 4165.743160000000 1865.262820000000 35204.316400000003 -4125.080570000000 -1685.119140000000 -4165.743160000000 0.000000000000 10603.365200000000 -4125.080570000000 5392.974610000000 1 33 60 3524.000000000000 0.000000000000 0.000000000000 0.000000000000 7911.368160000000 -1228.749630000000 0.000000000000 3524.000000000000 0.000000000000 -7911.368160000000 0.000000000000 -1866.630980000000 0.000000000000 0.000000000000 3524.000000000000 1228.749630000000 1866.630980000000 0.000000000000 0.000000000000 -7911.368160000000 1228.749630000000 18826.603500000001 905.779602000000 4369.752440000000 7911.368160000000 0.000000000000 1866.630980000000 905.779602000000 19570.324199999999 -2799.453860000000 -1228.749630000000 -1866.630980000000 0.000000000000 4369.752440000000 -2799.453860000000 2328.596190000000 1 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14005.166999999999 1207.358890000000 0.000000000000 5000.000000000000 0.000000000000 -14005.166999999999 0.000000000000 2204.659910000000 0.000000000000 0.000000000000 5000.000000000000 -1207.358890000000 -2204.659910000000 0.000000000000 0.000000000000 -14005.166999999999 -1207.358890000000 40854.464800000002 1454.416500000000 -6863.215330000000 14005.166999999999 0.000000000000 -2204.659910000000 1454.416500000000 42999.691400000003 3717.794190000000 1207.358890000000 2204.659910000000 0.000000000000 -6863.215330000000 3717.794190000000 4372.354000000000 1 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11688.080099999999 -464.592285000000 0.000000000000 5000.000000000000 0.000000000000 -11688.080099999999 0.000000000000 395.405151000000 0.000000000000 0.000000000000 5000.000000000000 464.592285000000 -395.405151000000 0.000000000000 0.000000000000 -11688.080099999999 464.592285000000 28802.275399999999 247.359360000000 -1012.123290000000 11688.080099999999 0.000000000000 -395.405151000000 247.359360000000 30666.687500000000 -794.465332000000 -464.592285000000 395.405151000000 0.000000000000 -1012.123290000000 -794.465332000000 2514.247070000000 1 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11516.600600000000 -627.145264000000 0.000000000000 5000.000000000000 0.000000000000 -11516.600600000000 0.000000000000 1174.261840000000 0.000000000000 0.000000000000 5000.000000000000 627.145264000000 -1174.261840000000 0.000000000000 0.000000000000 -11516.600600000000 627.145264000000 28445.625000000000 -308.272369000000 -2218.276370000000 11516.600600000000 0.000000000000 -1174.261840000000 -308.272369000000 30516.802700000000 -996.774353000000 -627.145264000000 1174.261840000000 0.000000000000 -2218.276370000000 -996.774353000000 2748.492430000000 1 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10758.340800000000 -303.740845000000 0.000000000000 5000.000000000000 0.000000000000 -10758.340800000000 0.000000000000 1513.162840000000 0.000000000000 0.000000000000 5000.000000000000 303.740845000000 -1513.162840000000 0.000000000000 0.000000000000 -10758.340800000000 303.740845000000 24616.431600000000 319.526703000000 -3497.578120000000 10758.340800000000 0.000000000000 -1513.162840000000 319.526703000000 26928.314500000000 -315.557495000000 -303.740845000000 1513.162840000000 0.000000000000 -3497.578120000000 -315.557495000000 3242.240480000000 1 39 60 4488.000000000000 0.000000000000 0.000000000000 0.000000000000 7227.757320000000 -1095.707150000000 0.000000000000 4488.000000000000 0.000000000000 -7227.757320000000 0.000000000000 1893.549440000000 0.000000000000 0.000000000000 4488.000000000000 1095.707150000000 -1893.549440000000 0.000000000000 0.000000000000 -7227.757320000000 1095.707150000000 12362.842800000000 -346.118042000000 -2642.851070000000 7227.757320000000 0.000000000000 -1893.549440000000 -346.118042000000 14847.695299999999 -1754.072140000000 -1095.707150000000 1893.549440000000 0.000000000000 -2642.851070000000 -1754.072140000000 3485.304200000000 1 47 60 2921.000000000000 0.000000000000 0.000000000000 0.000000000000 6045.793950000000 -1043.788940000000 0.000000000000 2921.000000000000 0.000000000000 -6045.793950000000 0.000000000000 -1943.957150000000 0.000000000000 0.000000000000 2921.000000000000 1043.788940000000 1943.957150000000 0.000000000000 0.000000000000 -6045.793950000000 1043.788940000000 13777.663100000000 810.340515000000 4282.325680000000 6045.793950000000 0.000000000000 1943.957150000000 810.340515000000 14729.811500000000 -2225.622800000000 -1043.788940000000 -1943.957150000000 0.000000000000 4282.325680000000 -2225.622800000000 2228.775630000000 1 48 60 4072.000000000000 0.000000000000 0.000000000000 0.000000000000 10187.924800000001 -818.482239000000 0.000000000000 4072.000000000000 0.000000000000 -10187.924800000001 0.000000000000 -919.888184000000 0.000000000000 0.000000000000 4072.000000000000 818.482239000000 919.888184000000 0.000000000000 0.000000000000 -10187.924800000001 818.482239000000 26907.425800000001 704.263306000000 2434.962160000000 10187.924800000001 0.000000000000 919.888184000000 704.263306000000 28472.212899999999 -1895.936890000000 -818.482239000000 -919.888184000000 0.000000000000 2434.962160000000 -1895.936890000000 2980.021480000000 1 49 60 4110.000000000000 0.000000000000 0.000000000000 0.000000000000 11693.059600000001 -545.793762000000 0.000000000000 4110.000000000000 0.000000000000 -11693.059600000001 0.000000000000 461.859009000000 0.000000000000 0.000000000000 4110.000000000000 545.793762000000 -461.859009000000 0.000000000000 0.000000000000 -11693.059600000001 545.793762000000 34317.226600000002 -55.772125200000 -1500.046390000000 11693.059600000001 0.000000000000 -461.859009000000 -55.772125200000 35382.492200000001 -1690.422970000000 -545.793762000000 461.859009000000 0.000000000000 -1500.046390000000 -1690.422970000000 2046.054080000000 1 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14689.851600000000 1179.984860000000 0.000000000000 5000.000000000000 0.000000000000 -14689.851600000000 0.000000000000 3746.369380000000 0.000000000000 0.000000000000 5000.000000000000 -1179.984860000000 -3746.369380000000 0.000000000000 0.000000000000 -14689.851600000000 -1179.984860000000 44729.328099999999 1426.440920000000 -10808.765600000001 14689.851600000000 0.000000000000 -3746.369380000000 1426.440920000000 47277.242200000001 3290.270510000000 1179.984860000000 3746.369380000000 0.000000000000 -10808.765600000001 3290.270510000000 4894.409670000000 1 51 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16078.584999999999 2353.369140000000 0.000000000000 5000.000000000000 0.000000000000 -16078.584999999999 0.000000000000 4334.986820000000 0.000000000000 0.000000000000 5000.000000000000 -2353.369140000000 -4334.986820000000 0.000000000000 0.000000000000 -16078.584999999999 -2353.369140000000 54110.191400000003 2559.660640000000 -13875.286099999999 16078.584999999999 0.000000000000 -4334.986820000000 2559.660640000000 56253.417999999998 7493.498540000000 2353.369140000000 4334.986820000000 0.000000000000 -13875.286099999999 7493.498540000000 6542.503910000000 2 3 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11271.690399999999 304.362213000000 0.000000000000 5000.000000000000 0.000000000000 -11271.690399999999 0.000000000000 -4831.790530000000 0.000000000000 0.000000000000 5000.000000000000 -304.362213000000 4831.790530000000 0.000000000000 0.000000000000 -11271.690399999999 -304.362213000000 26579.279299999998 -477.512085000000 11329.705099999999 11271.690399999999 0.000000000000 4831.790530000000 -477.512085000000 31477.824199999999 967.593079000000 304.362213000000 -4831.790530000000 0.000000000000 11329.705099999999 967.593079000000 5396.613280000000 2 31 60 2335.000000000000 0.000000000000 0.000000000000 0.000000000000 5235.232420000000 167.662827000000 0.000000000000 2335.000000000000 0.000000000000 -5235.232420000000 0.000000000000 -2590.742430000000 0.000000000000 0.000000000000 2335.000000000000 -167.662827000000 2590.742430000000 0.000000000000 0.000000000000 -5235.232420000000 -167.662827000000 12229.457000000000 -215.963013000000 5882.834470000000 5235.232420000000 0.000000000000 2590.742430000000 -215.963013000000 15077.684600000001 523.783752000000 167.662827000000 -2590.742430000000 0.000000000000 5882.834470000000 523.783752000000 3170.705810000000 2 33 60 2710.000000000000 0.000000000000 0.000000000000 0.000000000000 5927.701660000000 -205.356979000000 0.000000000000 2710.000000000000 0.000000000000 -5927.701660000000 0.000000000000 -2430.766110000000 0.000000000000 0.000000000000 2710.000000000000 205.356979000000 2430.766110000000 0.000000000000 0.000000000000 -5927.701660000000 205.356979000000 13439.951200000000 166.753296000000 5348.304200000000 5927.701660000000 0.000000000000 2430.766110000000 166.753296000000 15502.095700000000 -391.010864000000 -205.356979000000 -2430.766110000000 0.000000000000 5348.304200000000 -391.010864000000 2653.392580000000 2 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14178.152300000000 2514.467530000000 0.000000000000 5000.000000000000 0.000000000000 -14178.152300000000 0.000000000000 -2205.294920000000 0.000000000000 0.000000000000 5000.000000000000 -2514.467530000000 2205.294920000000 0.000000000000 0.000000000000 -14178.152300000000 -2514.467530000000 43118.980499999998 -177.159729000000 5472.057620000000 14178.152300000000 0.000000000000 2205.294920000000 -177.159729000000 43782.660199999998 7642.985840000000 2514.467530000000 -2205.294920000000 0.000000000000 5472.057620000000 7642.985840000000 4961.910160000000 2 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11816.543000000000 794.717102000000 0.000000000000 5000.000000000000 0.000000000000 -11816.543000000000 0.000000000000 -1530.432130000000 0.000000000000 0.000000000000 5000.000000000000 -794.717102000000 1530.432130000000 0.000000000000 0.000000000000 -11816.543000000000 -794.717102000000 29506.160199999998 -333.456848000000 3938.876710000000 11816.543000000000 0.000000000000 1530.432130000000 -333.456848000000 31742.875000000000 2376.815920000000 794.717102000000 -1530.432130000000 0.000000000000 3938.876710000000 2376.815920000000 3286.919920000000 2 39 60 4582.000000000000 0.000000000000 0.000000000000 0.000000000000 8353.473630000000 64.410430900000 0.000000000000 4582.000000000000 0.000000000000 -8353.473630000000 0.000000000000 281.237610000000 0.000000000000 0.000000000000 4582.000000000000 -64.410430900000 -281.237610000000 0.000000000000 0.000000000000 -8353.473630000000 -64.410430900000 15669.689500000000 277.681793000000 -449.293823000000 8353.473630000000 0.000000000000 -281.237610000000 277.681793000000 17477.861300000000 122.484322000000 64.410430900000 281.237610000000 0.000000000000 -449.293823000000 122.484322000000 2390.858150000000 2 48 60 3248.000000000000 0.000000000000 0.000000000000 0.000000000000 8076.857420000000 584.708191000000 0.000000000000 3248.000000000000 0.000000000000 -8076.857420000000 0.000000000000 -1894.209350000000 0.000000000000 0.000000000000 3248.000000000000 -584.708191000000 1894.209350000000 0.000000000000 0.000000000000 -8076.857420000000 -584.708191000000 21209.541000000001 -49.448989900000 4620.630370000000 8076.857420000000 0.000000000000 1894.209350000000 -49.448989900000 23119.820299999999 1724.353150000000 584.708191000000 -1894.209350000000 0.000000000000 4620.630370000000 1724.353150000000 2909.468260000000 2 49 60 3301.000000000000 0.000000000000 0.000000000000 0.000000000000 9329.050780000000 947.989258000000 0.000000000000 3301.000000000000 0.000000000000 -9329.050780000000 0.000000000000 -1815.925420000000 0.000000000000 0.000000000000 3301.000000000000 -947.989258000000 1815.925420000000 0.000000000000 0.000000000000 -9329.050780000000 -947.989258000000 27312.806600000000 -327.863922000000 4886.803710000000 9329.050780000000 0.000000000000 1815.925420000000 -327.863922000000 28943.216799999998 2755.414060000000 947.989258000000 -1815.925420000000 0.000000000000 4886.803710000000 2755.414060000000 2666.869140000000 2 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15096.137699999999 3757.171630000000 0.000000000000 5000.000000000000 0.000000000000 -15096.137699999999 0.000000000000 271.608856000000 0.000000000000 0.000000000000 5000.000000000000 -3757.171630000000 -271.608856000000 0.000000000000 0.000000000000 -15096.137699999999 -3757.171630000000 49323.156300000002 533.944946000000 -699.006104000000 15096.137699999999 0.000000000000 -271.608856000000 533.944946000000 46511.480499999998 11384.659200000000 3757.171630000000 271.608856000000 0.000000000000 -699.006104000000 11384.659200000000 4149.034180000000 2 51 60 3669.000000000000 0.000000000000 0.000000000000 0.000000000000 11929.726600000000 3830.696290000000 0.000000000000 3669.000000000000 0.000000000000 -11929.726600000000 0.000000000000 205.330505000000 0.000000000000 0.000000000000 3669.000000000000 -3830.696290000000 -205.330505000000 0.000000000000 0.000000000000 -11929.726600000000 -3830.696290000000 43292.496099999997 454.482910000000 -678.773315000000 11929.726600000000 0.000000000000 -205.330505000000 454.482910000000 39389.488299999997 12496.544900000001 3830.696290000000 205.330505000000 0.000000000000 -678.773315000000 12496.544900000001 4874.011230000000 3 24 60 3909.000000000000 0.000000000000 0.000000000000 0.000000000000 11583.767599999999 -3725.526370000000 0.000000000000 3909.000000000000 0.000000000000 -11583.767599999999 0.000000000000 -3726.500240000000 0.000000000000 0.000000000000 3909.000000000000 3725.526370000000 3726.500240000000 0.000000000000 0.000000000000 -11583.767599999999 3725.526370000000 38196.871099999997 3529.843510000000 11028.234399999999 11583.767599999999 0.000000000000 3726.500240000000 3529.843510000000 38303.675799999997 -11081.870100000000 -3725.526370000000 -3726.500240000000 0.000000000000 11028.234399999999 -11081.870100000000 7314.596190000000 3 25 60 1986.000000000000 0.000000000000 0.000000000000 0.000000000000 6001.832030000000 -1923.848630000000 0.000000000000 1986.000000000000 0.000000000000 -6001.832030000000 0.000000000000 -1828.164060000000 0.000000000000 0.000000000000 1986.000000000000 1923.848630000000 1828.164060000000 0.000000000000 0.000000000000 -6001.832030000000 1923.848630000000 20053.564500000000 1771.806760000000 5505.283690000000 6001.832030000000 0.000000000000 1828.164060000000 1771.806760000000 19996.640599999999 -5806.099610000000 -1923.848630000000 -1828.164060000000 0.000000000000 5505.283690000000 -5806.099610000000 3673.582280000000 3 26 60 766.000000000000 0.000000000000 0.000000000000 0.000000000000 2437.425050000000 -667.894958000000 0.000000000000 766.000000000000 0.000000000000 -2437.425050000000 0.000000000000 -729.869812000000 0.000000000000 0.000000000000 766.000000000000 667.894958000000 729.869812000000 0.000000000000 0.000000000000 -2437.425050000000 667.894958000000 8413.375980000001 608.861145000000 2310.879640000000 2437.425050000000 0.000000000000 729.869812000000 608.861145000000 8545.402340000001 -2112.840580000000 -667.894958000000 -729.869812000000 0.000000000000 2310.879640000000 -2112.840580000000 1403.440190000000 3 29 60 4187.000000000000 0.000000000000 0.000000000000 0.000000000000 12220.603499999999 -3803.581300000000 0.000000000000 4187.000000000000 0.000000000000 -12220.603499999999 0.000000000000 -3638.808110000000 0.000000000000 0.000000000000 4187.000000000000 3803.581300000000 3638.808110000000 0.000000000000 0.000000000000 -12220.603499999999 3803.581300000000 39682.667999999998 3457.708980000000 10834.975600000000 12220.603499999999 0.000000000000 3638.808110000000 3457.708980000000 39737.597699999998 -11274.785200000000 -3803.581300000000 -3638.808110000000 0.000000000000 10834.975600000000 -11274.785200000000 7283.486330000000 3 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13824.645500000001 -4491.433110000000 0.000000000000 5000.000000000000 0.000000000000 -13824.645500000001 0.000000000000 -2854.245360000000 0.000000000000 0.000000000000 5000.000000000000 4491.433110000000 2854.245360000000 0.000000000000 0.000000000000 -13824.645500000001 4491.433110000000 43102.085899999998 2738.242190000000 8112.114260000000 13824.645500000001 0.000000000000 2854.245360000000 2738.242190000000 41220.058599999997 -12642.283200000000 -4491.433110000000 -2854.245360000000 0.000000000000 8112.114260000000 -12642.283200000000 6780.342290000000 3 32 60 2160.000000000000 0.000000000000 0.000000000000 0.000000000000 4456.863770000000 -1282.748290000000 0.000000000000 2160.000000000000 0.000000000000 -4456.863770000000 0.000000000000 -396.209625000000 0.000000000000 0.000000000000 2160.000000000000 1282.748290000000 396.209625000000 0.000000000000 0.000000000000 -4456.863770000000 1282.748290000000 10409.123000000000 433.596222000000 1103.707890000000 4456.863770000000 0.000000000000 396.209625000000 433.596222000000 10316.277300000000 -2823.141110000000 -1282.748290000000 -396.209625000000 0.000000000000 1103.707890000000 -2823.141110000000 1746.045040000000 3 33 60 2816.000000000000 0.000000000000 0.000000000000 0.000000000000 6474.650880000000 -1367.550780000000 0.000000000000 2816.000000000000 0.000000000000 -6474.650880000000 0.000000000000 951.138733000000 0.000000000000 0.000000000000 2816.000000000000 1367.550780000000 -951.138733000000 0.000000000000 0.000000000000 -6474.650880000000 1367.550780000000 16093.034200000000 -284.746643000000 -2119.638180000000 6474.650880000000 0.000000000000 -951.138733000000 -284.746643000000 15943.573200000001 -3238.535400000000 -1367.550780000000 951.138733000000 0.000000000000 -2119.638180000000 -3238.535400000000 1566.634520000000 3 34 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12106.156300000001 -1691.905030000000 0.000000000000 5000.000000000000 0.000000000000 -12106.156300000001 0.000000000000 2365.650880000000 0.000000000000 0.000000000000 5000.000000000000 1691.905030000000 -2365.650880000000 0.000000000000 0.000000000000 -12106.156300000001 1691.905030000000 31123.367200000001 -716.594727000000 -5996.145510000000 12106.156300000001 0.000000000000 -2365.650880000000 -716.594727000000 31972.560500000000 -3862.030520000000 -1691.905030000000 2365.650880000000 0.000000000000 -5996.145510000000 -3862.030520000000 2183.106200000000 3 35 60 3883.000000000000 0.000000000000 0.000000000000 0.000000000000 10172.162100000000 -1129.418330000000 0.000000000000 3883.000000000000 0.000000000000 -10172.162100000000 0.000000000000 2073.774900000000 0.000000000000 0.000000000000 3883.000000000000 1129.418330000000 -2073.774900000000 0.000000000000 0.000000000000 -10172.162100000000 1129.418330000000 27616.460899999998 -579.968262000000 -5482.078610000000 10172.162100000000 0.000000000000 -2073.774900000000 -579.968262000000 28603.318400000000 -2851.182130000000 -1129.418330000000 2073.774900000000 0.000000000000 -5482.078610000000 -2851.182130000000 1728.958370000000 3 36 60 4320.000000000000 0.000000000000 0.000000000000 0.000000000000 10155.761699999999 -1524.975100000000 0.000000000000 4320.000000000000 0.000000000000 -10155.761699999999 0.000000000000 2084.128910000000 0.000000000000 0.000000000000 4320.000000000000 1524.975100000000 -2084.128910000000 0.000000000000 0.000000000000 -10155.761699999999 1524.975100000000 25228.828099999999 -661.608826000000 -5128.803220000000 10155.761699999999 0.000000000000 -2084.128910000000 -661.608826000000 25944.349600000001 -3428.759520000000 -1524.975100000000 2084.128910000000 0.000000000000 -5128.803220000000 -3428.759520000000 1930.390990000000 3 37 60 3312.000000000000 0.000000000000 0.000000000000 0.000000000000 7986.243160000000 -1110.523680000000 0.000000000000 3312.000000000000 0.000000000000 -7986.243160000000 0.000000000000 1677.726930000000 0.000000000000 0.000000000000 3312.000000000000 1110.523680000000 -1677.726930000000 0.000000000000 0.000000000000 -7986.243160000000 1110.523680000000 20048.441400000000 -525.554138000000 -4138.422360000000 7986.243160000000 0.000000000000 -1677.726930000000 -525.554138000000 20711.078099999999 -2600.408690000000 -1110.523680000000 1677.726930000000 0.000000000000 -4138.422360000000 -2600.408690000000 1473.376830000000 3 38 60 3676.000000000000 0.000000000000 0.000000000000 0.000000000000 7704.910640000000 -1340.539550000000 0.000000000000 3676.000000000000 0.000000000000 -7704.910640000000 0.000000000000 1736.105830000000 0.000000000000 0.000000000000 3676.000000000000 1340.539550000000 -1736.105830000000 0.000000000000 0.000000000000 -7704.910640000000 1340.539550000000 17192.955099999999 -585.323364000000 -3814.082520000000 7704.910640000000 0.000000000000 -1736.105830000000 -585.323364000000 17744.197300000000 -2720.116940000000 -1340.539550000000 1736.105830000000 0.000000000000 -3814.082520000000 -2720.116940000000 1585.710080000000 3 40 60 1803.000000000000 0.000000000000 0.000000000000 0.000000000000 3091.514160000000 -730.212158000000 0.000000000000 1803.000000000000 0.000000000000 -3091.514160000000 0.000000000000 -1124.479490000000 0.000000000000 0.000000000000 1803.000000000000 730.212158000000 1124.479490000000 0.000000000000 0.000000000000 -3091.514160000000 730.212158000000 5773.902340000000 433.548584000000 1848.311520000000 3091.514160000000 0.000000000000 1124.479490000000 433.548584000000 6816.324710000000 -1231.504030000000 -730.212158000000 -1124.479490000000 0.000000000000 1848.311520000000 -1231.504030000000 1648.913330000000 3 41 60 3684.000000000000 0.000000000000 0.000000000000 0.000000000000 7077.611820000000 -1680.006960000000 0.000000000000 3684.000000000000 0.000000000000 -7077.611820000000 0.000000000000 69.656906100000 0.000000000000 0.000000000000 3684.000000000000 1680.006960000000 -69.656906100000 0.000000000000 0.000000000000 -7077.611820000000 1680.006960000000 14745.893599999999 66.763603200000 -82.797988900000 7077.611820000000 0.000000000000 -69.656906100000 66.763603200000 15553.282200000000 -3236.626710000000 -1680.006960000000 69.656906100000 0.000000000000 -82.797988900000 -3236.626710000000 2463.516360000000 3 42 60 2487.000000000000 0.000000000000 0.000000000000 0.000000000000 5214.895510000000 -1491.897340000000 0.000000000000 2487.000000000000 0.000000000000 -5214.895510000000 0.000000000000 -2204.858640000000 0.000000000000 0.000000000000 2487.000000000000 1491.897340000000 2204.858640000000 0.000000000000 0.000000000000 -5214.895510000000 1491.897340000000 12621.994100000000 1329.250370000000 4585.050290000000 5214.895510000000 0.000000000000 2204.858640000000 1329.250370000000 13829.546899999999 -3400.016600000000 -1491.897340000000 -2204.858640000000 0.000000000000 4585.050290000000 -3400.016600000000 3461.712890000000 3 44 60 2651.000000000000 0.000000000000 0.000000000000 0.000000000000 5732.777830000000 -1747.839840000000 0.000000000000 2651.000000000000 0.000000000000 -5732.777830000000 0.000000000000 -2819.711910000000 0.000000000000 0.000000000000 2651.000000000000 1747.839840000000 2819.711910000000 0.000000000000 0.000000000000 -5732.777830000000 1747.839840000000 13828.925800000001 1861.849980000000 6124.711910000000 5732.777830000000 0.000000000000 2819.711910000000 1861.849980000000 15584.605500000000 -3745.979490000000 -1747.839840000000 -2819.711910000000 0.000000000000 6124.711910000000 -3745.979490000000 4292.511720000000 3 45 60 1677.000000000000 0.000000000000 0.000000000000 0.000000000000 3727.529790000000 -1172.087040000000 0.000000000000 1677.000000000000 0.000000000000 -3727.529790000000 0.000000000000 -1804.859500000000 0.000000000000 0.000000000000 1677.000000000000 1172.087040000000 1804.859500000000 0.000000000000 0.000000000000 -3727.529790000000 1172.087040000000 9283.623050000000 1259.306640000000 4029.293700000000 3727.529790000000 0.000000000000 1804.859500000000 1259.306640000000 10328.121100000000 -2583.927980000000 -1172.087040000000 -1804.859500000000 0.000000000000 4029.293700000000 -2583.927980000000 2868.586430000000 3 46 60 940.000000000000 0.000000000000 0.000000000000 0.000000000000 1875.672240000000 -449.446228000000 0.000000000000 940.000000000000 0.000000000000 -1875.672240000000 0.000000000000 -785.645447000000 0.000000000000 0.000000000000 940.000000000000 449.446228000000 785.645447000000 0.000000000000 0.000000000000 -1875.672240000000 449.446228000000 4087.297120000000 373.262817000000 1577.003050000000 1875.672240000000 0.000000000000 785.645447000000 373.262817000000 4655.999020000000 -915.927551000000 -449.446228000000 -785.645447000000 0.000000000000 1577.003050000000 -915.927551000000 1071.721440000000 3 48 60 4875.000000000000 0.000000000000 0.000000000000 0.000000000000 12765.383800000000 -3294.871830000000 0.000000000000 4875.000000000000 0.000000000000 -12765.383800000000 0.000000000000 547.726379000000 0.000000000000 0.000000000000 4875.000000000000 3294.871830000000 -547.726379000000 0.000000000000 0.000000000000 -12765.383800000000 3294.871830000000 37304.781300000002 280.615265000000 -1384.535280000000 12765.383800000000 0.000000000000 -547.726379000000 280.615265000000 35791.156300000002 -8804.838870000000 -3294.871830000000 547.726379000000 0.000000000000 -1384.535280000000 -8804.838870000000 4211.863280000000 3 49 60 2264.000000000000 0.000000000000 0.000000000000 0.000000000000 6228.030760000000 -798.146057000000 0.000000000000 2264.000000000000 0.000000000000 -6228.030760000000 0.000000000000 1506.869260000000 0.000000000000 0.000000000000 2264.000000000000 798.146057000000 -1506.869260000000 0.000000000000 0.000000000000 -6228.030760000000 798.146057000000 17800.441400000000 -525.357056000000 -4113.069820000000 6228.030760000000 0.000000000000 -1506.869260000000 -525.357056000000 18594.914100000002 -2204.781010000000 -798.146057000000 1506.869260000000 0.000000000000 -4113.069820000000 -2204.781010000000 1666.807370000000 4 8 60 3083.000000000000 0.000000000000 0.000000000000 0.000000000000 10184.546899999999 122.222313000000 0.000000000000 3083.000000000000 0.000000000000 -10184.546899999999 0.000000000000 3674.178710000000 0.000000000000 0.000000000000 3083.000000000000 -122.222313000000 -3674.178710000000 0.000000000000 0.000000000000 -10184.546899999999 -122.222313000000 33901.542999999998 94.271835300000 -12115.932600000000 10184.546899999999 0.000000000000 -3674.178710000000 94.271835300000 38302.886700000003 357.400665000000 122.222313000000 3674.178710000000 0.000000000000 -12115.932600000000 357.400665000000 4867.218260000000 4 24 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15133.081099999999 -2865.794680000000 0.000000000000 5000.000000000000 0.000000000000 -15133.081099999999 0.000000000000 4801.875000000000 0.000000000000 0.000000000000 5000.000000000000 2865.794680000000 -4801.875000000000 0.000000000000 0.000000000000 -15133.081099999999 2865.794680000000 48447.300799999997 -2982.007570000000 -14444.325199999999 15133.081099999999 0.000000000000 -4801.875000000000 -2982.007570000000 51014.175799999997 -8375.169920000000 -2865.794680000000 4801.875000000000 0.000000000000 -14444.325199999999 -8375.169920000000 7151.071780000000 4 25 60 3860.000000000000 0.000000000000 0.000000000000 0.000000000000 11955.910200000000 -1909.047240000000 0.000000000000 3860.000000000000 0.000000000000 -11955.910200000000 0.000000000000 3921.997310000000 0.000000000000 0.000000000000 3860.000000000000 1909.047240000000 -3921.997310000000 0.000000000000 0.000000000000 -11955.910200000000 1909.047240000000 38819.519500000002 -2148.454350000000 -12028.409200000000 11955.910200000000 0.000000000000 -3921.997310000000 -2148.454350000000 41413.566400000003 -5685.486820000000 -1909.047240000000 3921.997310000000 0.000000000000 -12028.409200000000 -5685.486820000000 5811.495120000000 4 26 60 3030.000000000000 0.000000000000 0.000000000000 0.000000000000 9554.206050000001 -1499.088620000000 0.000000000000 3030.000000000000 0.000000000000 -9554.206050000001 0.000000000000 3055.530030000000 0.000000000000 0.000000000000 3030.000000000000 1499.088620000000 -3055.530030000000 0.000000000000 0.000000000000 -9554.206050000001 1499.088620000000 31394.246100000000 -1706.928830000000 -9545.306640000001 9554.206050000001 0.000000000000 -3055.530030000000 -1706.928830000000 33492.546900000001 -4578.824220000000 -1499.088620000000 3055.530030000000 0.000000000000 -9545.306640000001 -4578.824220000000 4445.827640000000 4 29 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15190.027300000000 -2870.886960000000 0.000000000000 5000.000000000000 0.000000000000 -15190.027300000000 0.000000000000 4876.251460000000 0.000000000000 0.000000000000 5000.000000000000 2870.886960000000 -4876.251460000000 0.000000000000 0.000000000000 -15190.027300000000 2870.886960000000 48769.644500000002 -3026.515140000000 -14746.192400000000 15190.027300000000 0.000000000000 -4876.251460000000 -3026.515140000000 51519.890599999999 -8463.458979999999 -2870.886960000000 4876.251460000000 0.000000000000 -14746.192400000000 -8463.458979999999 7330.628420000000 4 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14808.170899999999 -2471.805910000000 0.000000000000 5000.000000000000 0.000000000000 -14808.170899999999 0.000000000000 4879.271480000000 0.000000000000 0.000000000000 5000.000000000000 2471.805910000000 -4879.271480000000 0.000000000000 0.000000000000 -14808.170899999999 2471.805910000000 46656.179700000001 -2560.880130000000 -14422.236300000000 14808.170899999999 0.000000000000 -4879.271480000000 -2560.880130000000 49345.835899999998 -6917.520510000000 -2471.805910000000 4879.271480000000 0.000000000000 -14422.236300000000 -6917.520510000000 7404.540530000000 4 31 60 4653.000000000000 0.000000000000 0.000000000000 0.000000000000 13299.317400000000 -3301.520510000000 0.000000000000 4653.000000000000 0.000000000000 -13299.317400000000 0.000000000000 3935.824220000000 0.000000000000 0.000000000000 4653.000000000000 3301.520510000000 -3935.824220000000 0.000000000000 0.000000000000 -13299.317400000000 3301.520510000000 41048.167999999998 -2972.928960000000 -11595.821300000000 13299.317400000000 0.000000000000 -3935.824220000000 -2972.928960000000 42584.460899999998 -9531.261720000000 -3301.520510000000 3935.824220000000 0.000000000000 -11595.821300000000 -9531.261720000000 6512.871580000000 4 32 60 1687.000000000000 0.000000000000 0.000000000000 0.000000000000 3748.436040000000 -924.838684000000 0.000000000000 1687.000000000000 0.000000000000 -3748.436040000000 0.000000000000 7.675886630000 0.000000000000 0.000000000000 1687.000000000000 924.838684000000 -7.675886630000 0.000000000000 0.000000000000 -3748.436040000000 924.838684000000 9235.548830000000 -98.988609300000 -331.390778000000 3748.436040000000 0.000000000000 -7.675886630000 -98.988609300000 9709.987300000001 -2189.907470000000 -924.838684000000 7.675886630000 0.000000000000 -331.390778000000 -2189.907470000000 1838.339230000000 4 42 60 2215.000000000000 0.000000000000 0.000000000000 0.000000000000 5172.558590000000 -1151.681640000000 0.000000000000 2215.000000000000 0.000000000000 -5172.558590000000 0.000000000000 -236.440567000000 0.000000000000 0.000000000000 2215.000000000000 1151.681640000000 236.440567000000 0.000000000000 0.000000000000 -5172.558590000000 1151.681640000000 13229.626000000000 -161.894714000000 68.475647000000 5172.558590000000 0.000000000000 236.440567000000 -161.894714000000 14264.590800000000 -2796.588620000000 -1151.681640000000 -236.440567000000 0.000000000000 68.475647000000 -2796.588620000000 2611.540530000000 4 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11087.603499999999 -2087.303220000000 0.000000000000 5000.000000000000 0.000000000000 -11087.603499999999 0.000000000000 1176.906250000000 0.000000000000 0.000000000000 5000.000000000000 2087.303220000000 -1176.906250000000 0.000000000000 0.000000000000 -11087.603499999999 2087.303220000000 26589.968799999999 -695.785217000000 -2911.521730000000 11087.603499999999 0.000000000000 -1176.906250000000 -695.785217000000 26288.691400000000 -4721.737300000000 -2087.303220000000 1176.906250000000 0.000000000000 -2911.521730000000 -4721.737300000000 2219.824460000000 4 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11269.473599999999 -2062.351560000000 0.000000000000 5000.000000000000 0.000000000000 -11269.473599999999 0.000000000000 1200.664920000000 0.000000000000 0.000000000000 5000.000000000000 2062.351560000000 -1200.664920000000 0.000000000000 0.000000000000 -11269.473599999999 2062.351560000000 27488.738300000001 -660.574707000000 -2969.457030000000 11269.473599999999 0.000000000000 -1200.664920000000 -660.574707000000 27238.615200000000 -4673.478520000000 -2062.351560000000 1200.664920000000 0.000000000000 -2969.457030000000 -4673.478520000000 2236.133540000000 4 47 60 1960.000000000000 0.000000000000 0.000000000000 0.000000000000 5042.229000000000 -1181.318730000000 0.000000000000 1960.000000000000 0.000000000000 -5042.229000000000 0.000000000000 1259.676270000000 0.000000000000 0.000000000000 1960.000000000000 1181.318730000000 -1259.676270000000 0.000000000000 0.000000000000 -5042.229000000000 1181.318730000000 14316.245100000000 -1024.911990000000 -3676.766850000000 5042.229000000000 0.000000000000 -1259.676270000000 -1024.911990000000 14835.264600000000 -3239.194580000000 -1181.318730000000 1259.676270000000 0.000000000000 -3676.766850000000 -3239.194580000000 2265.436770000000 5 6 60 2223.000000000000 0.000000000000 0.000000000000 0.000000000000 5922.407710000000 -1164.374020000000 0.000000000000 2223.000000000000 0.000000000000 -5922.407710000000 0.000000000000 712.859558000000 0.000000000000 0.000000000000 2223.000000000000 1164.374020000000 -712.859558000000 0.000000000000 0.000000000000 -5922.407710000000 1164.374020000000 17645.384800000000 -321.740234000000 -1973.024410000000 5922.407710000000 0.000000000000 -712.859558000000 -321.740234000000 17440.314500000000 -3196.849370000000 -1164.374020000000 712.859558000000 0.000000000000 -1973.024410000000 -3196.849370000000 1116.155030000000 5 11 60 2960.000000000000 0.000000000000 0.000000000000 0.000000000000 9625.988280000000 110.766510000000 0.000000000000 2960.000000000000 0.000000000000 -9625.988280000000 0.000000000000 -2567.516110000000 0.000000000000 0.000000000000 2960.000000000000 -110.766510000000 2567.516110000000 0.000000000000 0.000000000000 -9625.988280000000 -110.766510000000 31689.521499999999 -300.301544000000 8325.018550000001 9625.988280000000 0.000000000000 2567.516110000000 -300.301544000000 33887.425799999997 341.919189000000 110.766510000000 -2567.516110000000 0.000000000000 8325.018550000001 341.919189000000 2731.580320000000 5 15 60 2541.000000000000 0.000000000000 0.000000000000 0.000000000000 6616.160160000000 -707.499878000000 0.000000000000 2541.000000000000 0.000000000000 -6616.160160000000 0.000000000000 -1602.319820000000 0.000000000000 0.000000000000 2541.000000000000 707.499878000000 1602.319820000000 0.000000000000 0.000000000000 -6616.160160000000 707.499878000000 18316.831999999999 352.475128000000 4290.906740000000 6616.160160000000 0.000000000000 1602.319820000000 352.475128000000 19044.851600000002 -1788.831910000000 -707.499878000000 -1602.319820000000 0.000000000000 4290.906740000000 -1788.831910000000 1479.846680000000 5 40 60 2125.000000000000 0.000000000000 0.000000000000 0.000000000000 3612.622070000000 -699.288940000000 0.000000000000 2125.000000000000 0.000000000000 -3612.622070000000 0.000000000000 -32.374946600000 0.000000000000 0.000000000000 2125.000000000000 699.288940000000 32.374946600000 0.000000000000 0.000000000000 -3612.622070000000 699.288940000000 6481.452640000000 -87.086807300000 54.156665800000 3612.622070000000 0.000000000000 32.374946600000 -87.086807300000 7626.674800000000 -1208.103150000000 -699.288940000000 -32.374946600000 0.000000000000 54.156665800000 -1208.103150000000 1721.993410000000 6 8 60 2984.000000000000 0.000000000000 0.000000000000 0.000000000000 9700.840819999999 -358.479401000000 0.000000000000 2984.000000000000 0.000000000000 -9700.840819999999 0.000000000000 3591.075200000000 0.000000000000 0.000000000000 2984.000000000000 358.479401000000 -3591.075200000000 0.000000000000 0.000000000000 -9700.840819999999 358.479401000000 31941.871100000000 -454.013336000000 -11628.928700000000 9700.840819999999 0.000000000000 -3591.075200000000 -454.013336000000 36092.777300000002 -1216.490480000000 -358.479401000000 3591.075200000000 0.000000000000 -11628.928700000000 -1216.490480000000 4895.443850000000 6 9 60 976.000000000000 0.000000000000 0.000000000000 0.000000000000 3235.546880000000 -84.299171400000 0.000000000000 976.000000000000 0.000000000000 -3235.546880000000 0.000000000000 906.470398000000 0.000000000000 0.000000000000 976.000000000000 84.299171400000 -906.470398000000 0.000000000000 0.000000000000 -3235.546880000000 84.299171400000 10773.894500000000 -77.642067000000 -2997.063480000000 3235.546880000000 0.000000000000 -906.470398000000 -77.642067000000 11620.999000000000 -279.039520000000 -84.299171400000 906.470398000000 0.000000000000 -2997.063480000000 -279.039520000000 926.437012000000 6 10 60 841.000000000000 0.000000000000 0.000000000000 0.000000000000 2785.882080000000 -169.860260000000 0.000000000000 841.000000000000 0.000000000000 -2785.882080000000 0.000000000000 199.456451000000 0.000000000000 0.000000000000 841.000000000000 169.860260000000 -199.456451000000 0.000000000000 0.000000000000 -2785.882080000000 169.860260000000 9301.507809999999 78.759956400000 -687.675842000000 2785.882080000000 0.000000000000 -199.456451000000 78.759956400000 10073.267599999999 -560.375000000000 -169.860260000000 199.456451000000 0.000000000000 -687.675842000000 -560.375000000000 898.442688000000 6 24 60 2839.000000000000 0.000000000000 0.000000000000 0.000000000000 8697.534180000001 -1466.343140000000 0.000000000000 2839.000000000000 0.000000000000 -8697.534180000001 0.000000000000 2660.332280000000 0.000000000000 0.000000000000 2839.000000000000 1466.343140000000 -2660.332280000000 0.000000000000 0.000000000000 -8697.534180000001 1466.343140000000 28313.757799999999 -1491.630740000000 -8135.059570000000 8697.534180000001 0.000000000000 -2660.332280000000 -1491.630740000000 29564.671900000001 -4199.977540000000 -1466.343140000000 2660.332280000000 0.000000000000 -8135.059570000000 -4199.977540000000 3934.267580000000 6 25 60 3746.000000000000 0.000000000000 0.000000000000 0.000000000000 11436.738300000001 -2276.891850000000 0.000000000000 3746.000000000000 0.000000000000 -11436.738300000001 0.000000000000 3998.442380000000 0.000000000000 0.000000000000 3746.000000000000 2276.891850000000 -3998.442380000000 0.000000000000 0.000000000000 -11436.738300000001 2276.891850000000 37253.316400000003 -2622.528080000000 -12057.244100000000 11436.738300000001 0.000000000000 -3998.442380000000 -2622.528080000000 39656.210899999998 -6648.062990000000 -2276.891850000000 3998.442380000000 0.000000000000 -12057.244100000000 -6648.062990000000 6604.626460000000 6 26 60 2708.000000000000 0.000000000000 0.000000000000 0.000000000000 8423.510740000000 -1504.391850000000 0.000000000000 2708.000000000000 0.000000000000 -8423.510740000000 0.000000000000 2904.458980000000 0.000000000000 0.000000000000 2708.000000000000 1504.391850000000 -2904.458980000000 0.000000000000 0.000000000000 -8423.510740000000 1504.391850000000 27720.357400000001 -1822.771120000000 -8907.798830000000 8423.510740000000 0.000000000000 -2904.458980000000 -1822.771120000000 29641.214800000002 -4444.928220000000 -1504.391850000000 2904.458980000000 0.000000000000 -8907.798830000000 -4444.928220000000 4633.404790000000 6 29 60 3774.000000000000 0.000000000000 0.000000000000 0.000000000000 11269.720700000000 -2228.742920000000 0.000000000000 3774.000000000000 0.000000000000 -11269.720700000000 0.000000000000 3725.742190000000 0.000000000000 0.000000000000 3774.000000000000 2228.742920000000 -3725.742190000000 0.000000000000 0.000000000000 -11269.720700000000 2228.742920000000 36257.730499999998 -2412.441160000000 -11034.104499999999 11269.720700000000 0.000000000000 -3725.742190000000 -2412.441160000000 38057.929700000001 -6250.142090000000 -2228.742920000000 3725.742190000000 0.000000000000 -11034.104499999999 -6250.142090000000 5960.671880000000 6 30 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14006.423800000000 -2888.380860000000 0.000000000000 5000.000000000000 0.000000000000 -14006.423800000000 0.000000000000 5296.669920000000 0.000000000000 0.000000000000 5000.000000000000 2888.380860000000 -5296.669920000000 0.000000000000 0.000000000000 -14006.423800000000 2888.380860000000 43183.941400000003 -3175.557130000000 -14752.217800000000 14006.423800000000 0.000000000000 -5296.669920000000 -3175.557130000000 45981.363299999997 -7339.861820000000 -2888.380860000000 5296.669920000000 0.000000000000 -14752.217800000000 -7339.861820000000 9096.476559999999 6 31 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12983.104499999999 -4559.461910000000 0.000000000000 5000.000000000000 0.000000000000 -12983.104499999999 0.000000000000 5162.073730000000 0.000000000000 0.000000000000 5000.000000000000 4559.461910000000 -5162.073730000000 0.000000000000 0.000000000000 -12983.104499999999 4559.461910000000 38494.531300000002 -4971.664550000000 -13623.635700000001 12983.104499999999 0.000000000000 -5162.073730000000 -4971.664550000000 40146.398399999998 -11893.869100000000 -4559.461910000000 5162.073730000000 0.000000000000 -13623.635700000001 -11893.869100000000 10333.262699999999 6 42 60 3196.000000000000 0.000000000000 0.000000000000 0.000000000000 7263.392580000000 -2381.541020000000 0.000000000000 3196.000000000000 0.000000000000 -7263.392580000000 0.000000000000 1066.118290000000 0.000000000000 0.000000000000 3196.000000000000 2381.541020000000 -1066.118290000000 0.000000000000 0.000000000000 -7263.392580000000 2381.541020000000 19012.410199999998 -1406.492190000000 -2882.041500000000 7263.392580000000 0.000000000000 -1066.118290000000 -1406.492190000000 19089.789100000002 -5609.877440000000 -2381.541020000000 1066.118290000000 0.000000000000 -2882.041500000000 -5609.877440000000 4345.179690000000 6 43 60 1841.000000000000 0.000000000000 0.000000000000 0.000000000000 3791.500000000000 -724.970276000000 0.000000000000 1841.000000000000 0.000000000000 -3791.500000000000 0.000000000000 -166.164047000000 0.000000000000 0.000000000000 1841.000000000000 724.970276000000 166.164047000000 0.000000000000 0.000000000000 -3791.500000000000 724.970276000000 8634.504880000000 -61.505546600000 101.725426000000 3791.500000000000 0.000000000000 166.164047000000 -61.505546600000 8672.307620000000 -1525.321170000000 -724.970276000000 -166.164047000000 0.000000000000 101.725426000000 -1525.321170000000 919.838806000000 6 44 60 3938.000000000000 0.000000000000 0.000000000000 0.000000000000 8663.726559999999 -1844.188110000000 0.000000000000 3938.000000000000 0.000000000000 -8663.726559999999 0.000000000000 513.303528000000 0.000000000000 0.000000000000 3938.000000000000 1844.188110000000 -513.303528000000 0.000000000000 0.000000000000 -8663.726559999999 1844.188110000000 20818.298800000000 -321.257874000000 -1305.061280000000 8663.726559999999 0.000000000000 -513.303528000000 -321.257874000000 20322.310500000000 -4052.966800000000 -1844.188110000000 513.303528000000 0.000000000000 -1305.061280000000 -4052.966800000000 1783.912110000000 6 45 60 4532.000000000000 0.000000000000 0.000000000000 0.000000000000 10246.806600000000 -2221.555660000000 0.000000000000 4532.000000000000 0.000000000000 -10246.806600000000 0.000000000000 861.736877000000 0.000000000000 0.000000000000 4532.000000000000 2221.555660000000 -861.736877000000 0.000000000000 0.000000000000 -10246.806600000000 2221.555660000000 25350.253900000000 -521.280396000000 -2175.263180000000 10246.806600000000 0.000000000000 -861.736877000000 -521.280396000000 24804.458999999999 -5010.095210000000 -2221.555660000000 861.736877000000 0.000000000000 -2175.263180000000 -5010.095210000000 2295.079350000000 6 46 60 2003.000000000000 0.000000000000 0.000000000000 0.000000000000 4160.611820000000 -859.448364000000 0.000000000000 2003.000000000000 0.000000000000 -4160.611820000000 0.000000000000 129.701187000000 0.000000000000 0.000000000000 2003.000000000000 859.448364000000 -129.701187000000 0.000000000000 0.000000000000 -4160.611820000000 859.448364000000 9592.857420000000 -197.733429000000 -722.626831000000 4160.611820000000 0.000000000000 -129.701187000000 -197.733429000000 9739.529300000000 -1823.885990000000 -859.448364000000 129.701187000000 0.000000000000 -722.626831000000 -1823.885990000000 1293.570070000000 6 47 60 3870.000000000000 0.000000000000 0.000000000000 0.000000000000 9113.466800000000 -3277.913820000000 0.000000000000 3870.000000000000 0.000000000000 -9113.466800000000 0.000000000000 2969.092290000000 0.000000000000 0.000000000000 3870.000000000000 3277.913820000000 -2969.092290000000 0.000000000000 0.000000000000 -9113.466800000000 3277.913820000000 24895.125000000000 -3086.576900000000 -7502.887700000000 9113.466800000000 0.000000000000 -2969.092290000000 -3086.576900000000 25291.587899999999 -7951.343750000000 -3277.913820000000 2969.092290000000 0.000000000000 -7502.887700000000 -7951.343750000000 6612.285160000000 7 9 60 3218.000000000000 0.000000000000 0.000000000000 0.000000000000 9668.087890000001 -805.096802000000 0.000000000000 3218.000000000000 0.000000000000 -9668.087890000001 0.000000000000 -2032.907590000000 0.000000000000 0.000000000000 3218.000000000000 805.096802000000 2032.907590000000 0.000000000000 0.000000000000 -9668.087890000001 805.096802000000 29851.978500000001 1118.655400000000 6544.909670000000 9668.087890000001 0.000000000000 2032.907590000000 1118.655400000000 32898.929700000001 -2612.027830000000 -805.096802000000 -2032.907590000000 0.000000000000 6544.909670000000 -2612.027830000000 4068.970700000000 7 10 60 2073.000000000000 0.000000000000 0.000000000000 0.000000000000 6205.181150000000 -642.395142000000 0.000000000000 2073.000000000000 0.000000000000 -6205.181150000000 0.000000000000 -1987.120240000000 0.000000000000 0.000000000000 2073.000000000000 642.395142000000 1987.120240000000 0.000000000000 0.000000000000 -6205.181150000000 642.395142000000 19091.818400000000 797.129639000000 6127.096680000000 6205.181150000000 0.000000000000 1987.120240000000 797.129639000000 21496.339800000002 -2008.419560000000 -642.395142000000 -1987.120240000000 0.000000000000 6127.096680000000 -2008.419560000000 3012.114990000000 7 24 60 3247.000000000000 0.000000000000 0.000000000000 0.000000000000 8579.305660000000 -1461.070310000000 0.000000000000 3247.000000000000 0.000000000000 -8579.305660000000 0.000000000000 1129.895510000000 0.000000000000 0.000000000000 3247.000000000000 1461.070310000000 -1129.895510000000 0.000000000000 0.000000000000 -8579.305660000000 1461.070310000000 24185.400399999999 -759.235718000000 -3009.898930000000 8579.305660000000 0.000000000000 -1129.895510000000 -759.235718000000 23937.515599999999 -3691.421880000000 -1461.070310000000 1129.895510000000 0.000000000000 -3009.898930000000 -3691.421880000000 2013.862180000000 7 25 60 4483.000000000000 0.000000000000 0.000000000000 0.000000000000 11869.350600000000 -2295.733400000000 0.000000000000 4483.000000000000 0.000000000000 -11869.350600000000 0.000000000000 2290.095460000000 0.000000000000 0.000000000000 4483.000000000000 2295.733400000000 -2290.095460000000 0.000000000000 0.000000000000 -11869.350600000000 2295.733400000000 33723.343800000002 -1392.303710000000 -5893.775390000000 11869.350600000000 0.000000000000 -2290.095460000000 -1392.303710000000 33221.671900000001 -5811.827150000000 -2295.733400000000 2290.095460000000 0.000000000000 -5893.775390000000 -5811.827150000000 3556.810790000000 7 26 60 2959.000000000000 0.000000000000 0.000000000000 0.000000000000 7922.698730000000 -1638.033570000000 0.000000000000 2959.000000000000 0.000000000000 -7922.698730000000 0.000000000000 1712.404050000000 0.000000000000 0.000000000000 2959.000000000000 1638.033570000000 -1712.404050000000 0.000000000000 0.000000000000 -7922.698730000000 1638.033570000000 22655.035199999998 -1194.971310000000 -4430.948240000000 7922.698730000000 0.000000000000 -1712.404050000000 -1194.971310000000 22682.113300000001 -4228.393550000000 -1638.033570000000 1712.404050000000 0.000000000000 -4430.948240000000 -4228.393550000000 2539.721680000000 7 28 60 1123.000000000000 0.000000000000 0.000000000000 0.000000000000 3309.239500000000 -132.117447000000 0.000000000000 1123.000000000000 0.000000000000 -3309.239500000000 0.000000000000 287.142090000000 0.000000000000 0.000000000000 1123.000000000000 132.117447000000 -287.142090000000 0.000000000000 0.000000000000 -3309.239500000000 132.117447000000 9879.683590000001 -62.194889100000 -858.131897000000 3309.239500000000 0.000000000000 -287.142090000000 -62.194889100000 9875.096680000001 -422.373901000000 -132.117447000000 287.142090000000 0.000000000000 -858.131897000000 -422.373901000000 209.971527000000 7 29 60 4432.000000000000 0.000000000000 0.000000000000 0.000000000000 11714.978499999999 -2192.801510000000 0.000000000000 4432.000000000000 0.000000000000 -11714.978499999999 0.000000000000 869.265442000000 0.000000000000 0.000000000000 4432.000000000000 2192.801510000000 -869.265442000000 0.000000000000 0.000000000000 -11714.978499999999 2192.801510000000 33063.613299999997 -944.583923000000 -2124.088380000000 11714.978499999999 0.000000000000 -869.265442000000 -944.583923000000 33554.824200000003 -5597.962400000000 -2192.801510000000 869.265442000000 0.000000000000 -2124.088380000000 -5597.962400000000 3673.218260000000 7 30 60 3706.000000000000 0.000000000000 0.000000000000 0.000000000000 9403.223630000000 -2000.604000000000 0.000000000000 3706.000000000000 0.000000000000 -9403.223630000000 0.000000000000 1922.133790000000 0.000000000000 0.000000000000 3706.000000000000 2000.604000000000 -1922.133790000000 0.000000000000 0.000000000000 -9403.223630000000 2000.604000000000 25780.087899999999 -1382.742430000000 -4810.604000000000 9403.223630000000 0.000000000000 -1922.133790000000 -1382.742430000000 25590.341799999998 -4859.912110000000 -2000.604000000000 1922.133790000000 0.000000000000 -4810.604000000000 -4859.912110000000 3105.885740000000 7 31 60 2287.000000000000 0.000000000000 0.000000000000 0.000000000000 5322.958980000000 -1508.610350000000 0.000000000000 2287.000000000000 0.000000000000 -5322.958980000000 0.000000000000 600.217407000000 0.000000000000 0.000000000000 2287.000000000000 1508.610350000000 -600.217407000000 0.000000000000 0.000000000000 -5322.958980000000 1508.610350000000 13768.199199999999 -623.056702000000 -1597.522950000000 5322.958980000000 0.000000000000 -600.217407000000 -623.056702000000 13371.923800000000 -3623.709470000000 -1508.610350000000 600.217407000000 0.000000000000 -1597.522950000000 -3623.709470000000 1853.325680000000 7 43 60 2563.000000000000 0.000000000000 0.000000000000 0.000000000000 6065.102540000000 -605.242981000000 0.000000000000 2563.000000000000 0.000000000000 -6065.102540000000 0.000000000000 -2352.664550000000 0.000000000000 0.000000000000 2563.000000000000 605.242981000000 2352.664550000000 0.000000000000 0.000000000000 -6065.102540000000 605.242981000000 15650.089800000000 589.489807000000 6213.486330000000 6065.102540000000 0.000000000000 2352.664550000000 589.489807000000 18396.234400000001 -1409.227910000000 -605.242981000000 -2352.664550000000 0.000000000000 6213.486330000000 -1409.227910000000 3070.975340000000 7 44 60 4452.000000000000 0.000000000000 0.000000000000 0.000000000000 9845.657230000001 -1760.282470000000 0.000000000000 4452.000000000000 0.000000000000 -9845.657230000001 0.000000000000 -2619.924800000000 0.000000000000 0.000000000000 4452.000000000000 1760.282470000000 2619.924800000000 0.000000000000 0.000000000000 -9845.657230000001 1760.282470000000 24723.333999999999 1081.269170000000 7245.631350000000 9845.657230000001 0.000000000000 2619.924800000000 1081.269170000000 26819.146499999999 -4039.366940000000 -1760.282470000000 -2619.924800000000 0.000000000000 7245.631350000000 -4039.366940000000 3767.802980000000 7 45 60 4012.000000000000 0.000000000000 0.000000000000 0.000000000000 9011.739260000000 -1576.126590000000 0.000000000000 4012.000000000000 0.000000000000 -9011.739260000000 0.000000000000 -2322.593510000000 0.000000000000 0.000000000000 4012.000000000000 1576.126590000000 2322.593510000000 0.000000000000 0.000000000000 -9011.739260000000 1576.126590000000 22660.773399999998 847.255005000000 6481.742680000000 9011.739260000000 0.000000000000 2322.593510000000 847.255005000000 24648.335899999998 -3504.333980000000 -1576.126590000000 -2322.593510000000 0.000000000000 6481.742680000000 -3504.333980000000 3518.433350000000 7 47 60 1559.000000000000 0.000000000000 0.000000000000 0.000000000000 2924.274170000000 -741.612000000000 0.000000000000 1559.000000000000 0.000000000000 -2924.274170000000 0.000000000000 -52.663421600000 0.000000000000 0.000000000000 1559.000000000000 741.612000000000 52.663421600000 0.000000000000 0.000000000000 -2924.274170000000 741.612000000000 6269.462400000000 -183.746597000000 -196.659256000000 2924.274170000000 0.000000000000 52.663421600000 -183.746597000000 6187.931640000000 -1548.954100000000 -741.612000000000 -52.663421600000 0.000000000000 -196.659256000000 -1548.954100000000 887.587952000000 8 11 60 886.000000000000 0.000000000000 0.000000000000 0.000000000000 2253.543460000000 -626.238770000000 0.000000000000 886.000000000000 0.000000000000 -2253.543460000000 0.000000000000 -1069.137700000000 0.000000000000 0.000000000000 886.000000000000 626.238770000000 1069.137700000000 0.000000000000 0.000000000000 -2253.543460000000 626.238770000000 6234.430180000000 756.056213000000 2737.550540000000 2253.543460000000 0.000000000000 1069.137700000000 756.056213000000 7115.702640000000 -1592.122440000000 -626.238770000000 -1069.137700000000 0.000000000000 2737.550540000000 -1592.122440000000 1772.053960000000 8 25 60 2562.000000000000 0.000000000000 0.000000000000 0.000000000000 5016.859380000000 141.607574000000 0.000000000000 2562.000000000000 0.000000000000 -5016.859380000000 0.000000000000 618.430298000000 0.000000000000 0.000000000000 2562.000000000000 -141.607574000000 -618.430298000000 0.000000000000 0.000000000000 -5016.859380000000 -141.607574000000 10419.599600000000 235.021332000000 -1113.802370000000 5016.859380000000 0.000000000000 -618.430298000000 235.021332000000 10256.648400000000 155.389893000000 141.607574000000 618.430298000000 0.000000000000 -1113.802370000000 155.389893000000 752.425598000000 8 30 60 1821.000000000000 0.000000000000 0.000000000000 0.000000000000 3393.419920000000 -156.371964000000 0.000000000000 1821.000000000000 0.000000000000 -3393.419920000000 0.000000000000 323.303864000000 0.000000000000 0.000000000000 1821.000000000000 156.371964000000 -323.303864000000 0.000000000000 0.000000000000 -3393.419920000000 156.371964000000 6564.214840000000 71.825706500000 -653.143555000000 3393.419920000000 0.000000000000 -323.303864000000 71.825706500000 6635.382320000000 -288.890564000000 -156.371964000000 323.303864000000 0.000000000000 -653.143555000000 -288.890564000000 387.884918000000 8 44 60 1709.000000000000 0.000000000000 0.000000000000 0.000000000000 3743.567380000000 -1204.131710000000 0.000000000000 1709.000000000000 0.000000000000 -3743.567380000000 0.000000000000 -1397.607670000000 0.000000000000 0.000000000000 1709.000000000000 1204.131710000000 1397.607670000000 0.000000000000 0.000000000000 -3743.567380000000 1204.131710000000 9283.666990000000 1070.289670000000 3237.064210000000 3743.567380000000 0.000000000000 1397.607670000000 1070.289670000000 9887.256840000000 -2703.808590000000 -1204.131710000000 -1397.607670000000 0.000000000000 3237.064210000000 -2703.808590000000 2406.957520000000 8 45 60 1204.000000000000 0.000000000000 0.000000000000 0.000000000000 2564.151120000000 -772.499084000000 0.000000000000 1204.000000000000 0.000000000000 -2564.151120000000 0.000000000000 -724.247986000000 0.000000000000 0.000000000000 1204.000000000000 772.499084000000 724.247986000000 0.000000000000 0.000000000000 -2564.151120000000 772.499084000000 6167.522950000000 555.650208000000 1670.142090000000 2564.151120000000 0.000000000000 724.247986000000 555.650208000000 6324.878420000000 -1705.267940000000 -772.499084000000 -724.247986000000 0.000000000000 1670.142090000000 -1705.267940000000 1285.002200000000 9 11 60 4939.000000000000 0.000000000000 0.000000000000 0.000000000000 10980.311500000000 -1871.475460000000 0.000000000000 4939.000000000000 0.000000000000 -10980.311500000000 0.000000000000 -6343.635250000000 0.000000000000 0.000000000000 4939.000000000000 1871.475460000000 6343.635250000000 0.000000000000 0.000000000000 -10980.311500000000 1871.475460000000 25920.949199999999 2313.303710000000 14115.928700000000 10980.311500000000 0.000000000000 6343.635250000000 2313.303710000000 33313.128900000003 -4084.442870000000 -1871.475460000000 -6343.635250000000 0.000000000000 14115.928700000000 -4084.442870000000 9292.181640000001 9 24 60 3995.000000000000 0.000000000000 0.000000000000 0.000000000000 5880.082030000000 -542.271362000000 0.000000000000 3995.000000000000 0.000000000000 -5880.082030000000 0.000000000000 361.958374000000 0.000000000000 0.000000000000 3995.000000000000 542.271362000000 -361.958374000000 0.000000000000 0.000000000000 -5880.082030000000 542.271362000000 9351.579100000001 324.669189000000 -583.973450000000 5880.082030000000 0.000000000000 -361.958374000000 324.669189000000 9511.134770000001 -871.234680000000 -542.271362000000 361.958374000000 0.000000000000 -583.973450000000 -871.234680000000 1130.408810000000 9 26 60 3312.000000000000 0.000000000000 0.000000000000 0.000000000000 5244.892090000000 -235.398590000000 0.000000000000 3312.000000000000 0.000000000000 -5244.892090000000 0.000000000000 804.624268000000 0.000000000000 0.000000000000 3312.000000000000 235.398590000000 -804.624268000000 0.000000000000 0.000000000000 -5244.892090000000 235.398590000000 8883.116210000000 75.535743700000 -1168.399050000000 5244.892090000000 0.000000000000 -804.624268000000 75.535743700000 9003.364260000000 -493.791046000000 -235.398590000000 804.624268000000 0.000000000000 -1168.399050000000 -493.791046000000 627.333008000000 9 28 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11145.047900000000 -1833.360230000000 0.000000000000 5000.000000000000 0.000000000000 -11145.047900000000 0.000000000000 -1150.419190000000 0.000000000000 0.000000000000 5000.000000000000 1833.360230000000 1150.419190000000 0.000000000000 0.000000000000 -11145.047900000000 1833.360230000000 27512.044900000001 696.791931000000 3390.535160000000 11145.047900000000 0.000000000000 1150.419190000000 696.791931000000 27486.375000000000 -4260.314450000000 -1833.360230000000 -1150.419190000000 0.000000000000 3390.535160000000 -4260.314450000000 1961.380620000000 9 29 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7905.891600000000 -969.282776000000 0.000000000000 5000.000000000000 0.000000000000 -7905.891600000000 0.000000000000 85.093322800000 0.000000000000 0.000000000000 5000.000000000000 969.282776000000 -85.093322800000 0.000000000000 0.000000000000 -7905.891600000000 969.282776000000 13776.662100000000 417.593018000000 34.510944400000 7905.891600000000 0.000000000000 -85.093322800000 417.593018000000 14252.377000000000 -1702.392210000000 -969.282776000000 85.093322800000 0.000000000000 34.510944400000 -1702.392210000000 1652.708860000000 9 30 60 1131.000000000000 0.000000000000 0.000000000000 0.000000000000 1526.621830000000 -233.522644000000 0.000000000000 1131.000000000000 0.000000000000 -1526.621830000000 0.000000000000 -69.566543600000 0.000000000000 0.000000000000 1131.000000000000 233.522644000000 69.566543600000 0.000000000000 0.000000000000 -1526.621830000000 233.522644000000 2201.491940000000 64.588218700000 30.893732100000 1526.621830000000 0.000000000000 69.566543600000 64.588218700000 2271.786130000000 -297.453766000000 -233.522644000000 -69.566543600000 0.000000000000 30.893732100000 -297.453766000000 254.918839000000 9 43 60 2962.000000000000 0.000000000000 0.000000000000 0.000000000000 4956.055660000000 -1111.742310000000 0.000000000000 2962.000000000000 0.000000000000 -4956.055660000000 0.000000000000 -3085.956540000000 0.000000000000 0.000000000000 2962.000000000000 1111.742310000000 3085.956540000000 0.000000000000 0.000000000000 -4956.055660000000 1111.742310000000 9432.940430000001 1057.688350000000 5627.927250000000 4956.055660000000 0.000000000000 3085.956540000000 1057.688350000000 12648.513700000000 -1773.795780000000 -1111.742310000000 -3085.956540000000 0.000000000000 5627.927250000000 -1773.795780000000 4298.414550000000 9 44 60 4756.000000000000 0.000000000000 0.000000000000 0.000000000000 9080.249019999999 -2527.026860000000 0.000000000000 4756.000000000000 0.000000000000 -9080.249019999999 0.000000000000 -4625.504390000000 0.000000000000 0.000000000000 4756.000000000000 2527.026860000000 4625.504390000000 0.000000000000 0.000000000000 -9080.249019999999 2527.026860000000 19586.105500000001 2341.803710000000 9344.546880000000 9080.249019999999 0.000000000000 4625.504390000000 2341.803710000000 23414.043000000001 -4839.281740000000 -2527.026860000000 -4625.504390000000 0.000000000000 9344.546880000000 -4839.281740000000 6778.129880000000 9 45 60 3797.000000000000 0.000000000000 0.000000000000 0.000000000000 7151.223630000000 -1872.568240000000 0.000000000000 3797.000000000000 0.000000000000 -7151.223630000000 0.000000000000 -3649.656490000000 0.000000000000 0.000000000000 3797.000000000000 1872.568240000000 3649.656490000000 0.000000000000 0.000000000000 -7151.223630000000 1872.568240000000 15187.849600000000 1659.157710000000 7346.835940000000 7151.223630000000 0.000000000000 3649.656490000000 1659.157710000000 18470.673800000000 -3518.345950000000 -1872.568240000000 -3649.656490000000 0.000000000000 7346.835940000000 -3518.345950000000 5413.652830000000 10 12 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14587.970700000000 -432.768982000000 0.000000000000 5000.000000000000 0.000000000000 -14587.970700000000 0.000000000000 -4067.307130000000 0.000000000000 0.000000000000 5000.000000000000 432.768982000000 4067.307130000000 0.000000000000 0.000000000000 -14587.970700000000 432.768982000000 43273.101600000002 167.040482000000 11684.394500000000 14587.970700000000 0.000000000000 4067.307130000000 167.040482000000 47333.476600000002 -1178.872440000000 -432.768982000000 -4067.307130000000 0.000000000000 11684.394500000000 -1178.872440000000 4661.168460000000 10 13 60 4226.000000000000 0.000000000000 0.000000000000 0.000000000000 12967.861300000000 370.007355000000 0.000000000000 4226.000000000000 0.000000000000 -12967.861300000000 0.000000000000 -3959.770750000000 0.000000000000 0.000000000000 4226.000000000000 -370.007355000000 3959.770750000000 0.000000000000 0.000000000000 -12967.861300000000 -370.007355000000 40168.531300000002 -482.473328000000 12147.780300000000 12967.861300000000 0.000000000000 3959.770750000000 -482.473328000000 44565.164100000002 1164.227780000000 370.007355000000 -3959.770750000000 0.000000000000 12147.780300000000 1164.227780000000 4681.166990000000 10 15 60 2562.000000000000 0.000000000000 0.000000000000 0.000000000000 7458.015140000000 3.277833220000 0.000000000000 2562.000000000000 0.000000000000 -7458.015140000000 0.000000000000 -2961.149170000000 0.000000000000 0.000000000000 2562.000000000000 -3.277833220000 2961.149170000000 0.000000000000 0.000000000000 -7458.015140000000 -3.277833220000 21994.513700000000 44.507606500000 8559.653319999999 7458.015140000000 0.000000000000 2961.149170000000 44.507606500000 25561.503900000000 48.678577400000 3.277833220000 -2961.149170000000 0.000000000000 8559.653319999999 48.678577400000 3722.600100000000 10 17 60 4338.000000000000 0.000000000000 0.000000000000 0.000000000000 12592.975600000000 -186.860352000000 0.000000000000 4338.000000000000 0.000000000000 -12592.975600000000 0.000000000000 -4255.383300000000 0.000000000000 0.000000000000 4338.000000000000 186.860352000000 4255.383300000000 0.000000000000 0.000000000000 -12592.975600000000 186.860352000000 37112.667999999998 67.018775900000 12304.273400000000 12592.975600000000 0.000000000000 4255.383300000000 67.018775900000 41793.460899999998 -434.364349000000 -186.860352000000 -4255.383300000000 0.000000000000 12304.273400000000 -434.364349000000 5155.685060000000 10 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14315.383800000000 65.151115400000 0.000000000000 5000.000000000000 0.000000000000 -14315.383800000000 0.000000000000 -4956.269530000000 0.000000000000 0.000000000000 5000.000000000000 -65.151115400000 4956.269530000000 0.000000000000 0.000000000000 -14315.383800000000 -65.151115400000 41909.003900000003 -123.434364000000 14398.562500000000 14315.383800000000 0.000000000000 4956.269530000000 -123.434364000000 47184.843800000002 334.378998000000 65.151115400000 -4956.269530000000 0.000000000000 14398.562500000000 334.378998000000 5612.325680000000 10 28 60 2641.000000000000 0.000000000000 0.000000000000 0.000000000000 6072.511230000000 -1279.969480000000 0.000000000000 2641.000000000000 0.000000000000 -6072.511230000000 0.000000000000 770.865967000000 0.000000000000 0.000000000000 2641.000000000000 1279.969480000000 -770.865967000000 0.000000000000 0.000000000000 -6072.511230000000 1279.969480000000 15327.096700000000 -348.472656000000 -1692.736080000000 6072.511230000000 0.000000000000 -770.865967000000 -348.472656000000 14966.637699999999 -2999.812010000000 -1279.969480000000 770.865967000000 0.000000000000 -1692.736080000000 -2999.812010000000 999.789001000000 10 29 60 2232.000000000000 0.000000000000 0.000000000000 0.000000000000 3888.106450000000 -703.574890000000 0.000000000000 2232.000000000000 0.000000000000 -3888.106450000000 0.000000000000 -213.541855000000 0.000000000000 0.000000000000 2232.000000000000 703.574890000000 213.541855000000 0.000000000000 0.000000000000 -3888.106450000000 703.574890000000 7687.559570000000 76.665969800000 605.546082000000 3888.106450000000 0.000000000000 213.541855000000 76.665969800000 7908.090820000000 -1238.627560000000 -703.574890000000 -213.541855000000 0.000000000000 605.546082000000 -1238.627560000000 838.371887000000 10 43 60 4680.000000000000 0.000000000000 0.000000000000 0.000000000000 9461.448240000000 -1343.684450000000 0.000000000000 4680.000000000000 0.000000000000 -9461.448240000000 0.000000000000 -2296.334960000000 0.000000000000 0.000000000000 4680.000000000000 1343.684450000000 2296.334960000000 0.000000000000 0.000000000000 -9461.448240000000 1343.684450000000 21418.502000000000 593.358093000000 5091.459960000000 9461.448240000000 0.000000000000 2296.334960000000 593.358093000000 22406.831999999999 -2498.364010000000 -1343.684450000000 -2296.334960000000 0.000000000000 5091.459960000000 -2498.364010000000 2129.178710000000 10 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11700.726600000000 -1776.520390000000 0.000000000000 5000.000000000000 0.000000000000 -11700.726600000000 0.000000000000 -1915.186650000000 0.000000000000 0.000000000000 5000.000000000000 1776.520390000000 1915.186650000000 0.000000000000 0.000000000000 -11700.726600000000 1776.520390000000 29449.333999999999 475.411407000000 4820.826170000000 11700.726600000000 0.000000000000 1915.186650000000 475.411407000000 29763.919900000001 -3986.067380000000 -1776.520390000000 -1915.186650000000 0.000000000000 4820.826170000000 -3986.067380000000 2126.404540000000 10 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11302.891600000001 -1586.840820000000 0.000000000000 5000.000000000000 0.000000000000 -11302.891600000001 0.000000000000 -1890.094120000000 0.000000000000 0.000000000000 5000.000000000000 1586.840820000000 1890.094120000000 0.000000000000 0.000000000000 -11302.891600000001 1586.840820000000 27642.502000000000 350.833435000000 4696.458010000000 11302.891600000001 0.000000000000 1890.094120000000 350.833435000000 28165.193400000000 -3383.278320000000 -1586.840820000000 -1890.094120000000 0.000000000000 4696.458010000000 -3383.278320000000 2105.775150000000 11 13 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14376.364299999999 448.495117000000 0.000000000000 5000.000000000000 0.000000000000 -14376.364299999999 0.000000000000 125.957848000000 0.000000000000 0.000000000000 5000.000000000000 -448.495117000000 -125.957848000000 0.000000000000 0.000000000000 -14376.364299999999 -448.495117000000 42394.527300000002 -176.813400000000 -339.023682000000 14376.364299999999 0.000000000000 -125.957848000000 -176.813400000000 43469.707000000002 1575.210690000000 448.495117000000 125.957848000000 0.000000000000 -339.023682000000 1575.210690000000 1679.925420000000 11 18 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15251.163100000000 1201.134280000000 0.000000000000 5000.000000000000 0.000000000000 -15251.163100000000 0.000000000000 -2539.366460000000 0.000000000000 0.000000000000 5000.000000000000 -1201.134280000000 2539.366460000000 0.000000000000 0.000000000000 -15251.163100000000 -1201.134280000000 47568.730499999998 -781.897949000000 7655.251950000000 15251.163100000000 0.000000000000 2539.366460000000 -781.897949000000 48716.195299999999 3934.785640000000 1201.134280000000 -2539.366460000000 0.000000000000 7655.251950000000 3934.785640000000 2715.168460000000 11 20 60 4325.000000000000 0.000000000000 0.000000000000 0.000000000000 13647.038100000000 2515.302490000000 0.000000000000 4325.000000000000 0.000000000000 -13647.038100000000 0.000000000000 -3181.821290000000 0.000000000000 0.000000000000 4325.000000000000 -2515.302490000000 3181.821290000000 0.000000000000 0.000000000000 -13647.038100000000 -2515.302490000000 44925.847699999998 -2010.738530000000 9961.565430000001 13647.038100000000 0.000000000000 3181.821290000000 -2010.738530000000 45842.003900000003 8011.447750000000 2515.302490000000 -3181.821290000000 0.000000000000 9961.565430000001 8011.447750000000 4420.049320000000 11 21 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14476.774400000000 635.053345000000 0.000000000000 5000.000000000000 0.000000000000 -14476.774400000000 0.000000000000 -2376.936280000000 0.000000000000 0.000000000000 5000.000000000000 -635.053345000000 2376.936280000000 0.000000000000 0.000000000000 -14476.774400000000 -635.053345000000 43050.992200000001 -391.143097000000 6728.060550000000 14476.774400000000 0.000000000000 2376.936280000000 -391.143097000000 44106.203099999999 2263.440920000000 635.053345000000 -2376.936280000000 0.000000000000 6728.060550000000 2263.440920000000 2242.384770000000 11 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13062.858399999999 68.000183100000 0.000000000000 5000.000000000000 0.000000000000 -13062.858399999999 0.000000000000 -2609.774410000000 0.000000000000 0.000000000000 5000.000000000000 -68.000183100000 2609.774410000000 0.000000000000 0.000000000000 -13062.858399999999 -68.000183100000 34988.750000000000 -107.749115000000 6806.865230000000 13062.858399999999 0.000000000000 2609.774410000000 -107.749115000000 37115.578099999999 418.144623000000 68.000183100000 -2609.774410000000 0.000000000000 6806.865230000000 418.144623000000 2469.453610000000 11 23 60 3190.000000000000 0.000000000000 0.000000000000 0.000000000000 7621.410640000000 -447.742035000000 0.000000000000 3190.000000000000 0.000000000000 -7621.410640000000 0.000000000000 -2338.713620000000 0.000000000000 0.000000000000 3190.000000000000 447.742035000000 2338.713620000000 0.000000000000 0.000000000000 -7621.410640000000 447.742035000000 18706.511699999999 284.223450000000 5657.144530000000 7621.410640000000 0.000000000000 2338.713620000000 284.223450000000 20369.761699999999 -945.955017000000 -447.742035000000 -2338.713620000000 0.000000000000 5657.144530000000 -945.955017000000 2055.130860000000 11 44 60 4333.000000000000 0.000000000000 0.000000000000 0.000000000000 9192.509770000001 -2137.392330000000 0.000000000000 4333.000000000000 0.000000000000 -9192.509770000001 0.000000000000 646.058777000000 0.000000000000 0.000000000000 4333.000000000000 2137.392330000000 -646.058777000000 0.000000000000 0.000000000000 -9192.509770000001 2137.392330000000 20831.992200000001 -367.343201000000 -1397.277710000000 9192.509770000001 0.000000000000 -646.058777000000 -367.343201000000 19960.206999999999 -4486.425780000000 -2137.392330000000 646.058777000000 0.000000000000 -1397.277710000000 -4486.425780000000 1536.791870000000 11 45 60 4024.000000000000 0.000000000000 0.000000000000 0.000000000000 8470.558590000001 -1742.483890000000 0.000000000000 4024.000000000000 0.000000000000 -8470.558590000001 0.000000000000 430.981415000000 0.000000000000 0.000000000000 4024.000000000000 1742.483890000000 -430.981415000000 0.000000000000 0.000000000000 -8470.558590000001 1742.483890000000 18846.687500000000 -249.299896000000 -982.316711000000 8470.558590000001 0.000000000000 -430.981415000000 -249.299896000000 18350.769499999999 -3657.633790000000 -1742.483890000000 430.981415000000 0.000000000000 -982.316711000000 -3657.633790000000 1305.708250000000 12 19 60 1587.000000000000 0.000000000000 0.000000000000 0.000000000000 4391.942870000000 1403.738770000000 0.000000000000 1587.000000000000 0.000000000000 -4391.942870000000 0.000000000000 -2.091891530000 0.000000000000 0.000000000000 1587.000000000000 -1403.738770000000 2.091891530000 0.000000000000 0.000000000000 -4391.942870000000 -1403.738770000000 13522.527300000000 -14.235281000000 -60.686836200000 4391.942870000000 0.000000000000 2.091891530000 -14.235281000000 12437.024400000000 3885.386230000000 1403.738770000000 -2.091891530000 0.000000000000 -60.686836200000 3885.386230000000 1455.522580000000 12 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12392.239299999999 3341.124270000000 0.000000000000 5000.000000000000 0.000000000000 -12392.239299999999 0.000000000000 -1881.089360000000 0.000000000000 0.000000000000 5000.000000000000 -3341.124270000000 1881.089360000000 0.000000000000 0.000000000000 -12392.239299999999 -3341.124270000000 33578.695299999999 -1205.708130000000 4271.960450000000 12392.239299999999 0.000000000000 1881.089360000000 -1205.708130000000 32416.623000000000 8445.803710000000 3341.124270000000 -1881.089360000000 0.000000000000 4271.960450000000 8445.803710000000 3807.431400000000 12 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9258.784180000001 398.810394000000 0.000000000000 5000.000000000000 0.000000000000 -9258.784180000001 0.000000000000 -1879.512080000000 0.000000000000 0.000000000000 5000.000000000000 -398.810394000000 1879.512080000000 0.000000000000 0.000000000000 -9258.784180000001 -398.810394000000 17865.916000000001 -272.359894000000 3702.163330000000 9258.784180000001 0.000000000000 1879.512080000000 -272.359894000000 19099.927700000000 1005.821780000000 398.810394000000 -1879.512080000000 0.000000000000 3702.163330000000 1005.821780000000 1701.088750000000 13 19 60 1652.000000000000 0.000000000000 0.000000000000 0.000000000000 4074.210450000000 1284.642820000000 0.000000000000 1652.000000000000 0.000000000000 -4074.210450000000 0.000000000000 612.315735000000 0.000000000000 0.000000000000 1652.000000000000 -1284.642820000000 -612.315735000000 0.000000000000 0.000000000000 -4074.210450000000 -1284.642820000000 11170.948200000001 493.027710000000 -1505.113040000000 4074.210450000000 0.000000000000 -612.315735000000 493.027710000000 10457.822300000000 3175.986570000000 1284.642820000000 612.315735000000 0.000000000000 -1505.113040000000 3175.986570000000 1368.557740000000 13 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10900.865200000000 3032.082280000000 0.000000000000 5000.000000000000 0.000000000000 -10900.865200000000 0.000000000000 -1545.613770000000 0.000000000000 0.000000000000 5000.000000000000 -3032.082280000000 1545.613770000000 0.000000000000 0.000000000000 -10900.865200000000 -3032.082280000000 26147.658200000002 -700.459595000000 2840.383300000000 10900.865200000000 0.000000000000 1545.613770000000 -700.459595000000 25652.316400000000 6801.680180000000 3032.082280000000 -1545.613770000000 0.000000000000 2840.383300000000 6801.680180000000 3529.848630000000 13 21 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9461.069340000000 1774.851810000000 0.000000000000 5000.000000000000 0.000000000000 -9461.069340000000 0.000000000000 -2394.159670000000 0.000000000000 0.000000000000 5000.000000000000 -1774.851810000000 2394.159670000000 0.000000000000 0.000000000000 -9461.069340000000 -1774.851810000000 18911.107400000001 -859.770935000000 4458.116210000000 9461.069340000000 0.000000000000 2394.159670000000 -859.770935000000 19728.449199999999 3517.524170000000 1774.851810000000 -2394.159670000000 0.000000000000 4458.116210000000 3517.524170000000 2506.976810000000 13 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8345.665040000000 730.382935000000 0.000000000000 5000.000000000000 0.000000000000 -8345.665040000000 0.000000000000 -2459.762450000000 0.000000000000 0.000000000000 5000.000000000000 -730.382935000000 2459.762450000000 0.000000000000 0.000000000000 -8345.665040000000 -730.382935000000 14549.135700000001 -426.482727000000 4225.032230000000 8345.665040000000 0.000000000000 2459.762450000000 -426.482727000000 15882.561500000000 1442.292720000000 730.382935000000 -2459.762450000000 0.000000000000 4225.032230000000 1442.292720000000 1859.759640000000 14 19 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11203.140600000001 2670.292480000000 0.000000000000 5000.000000000000 0.000000000000 -11203.140600000001 0.000000000000 2229.202390000000 0.000000000000 0.000000000000 5000.000000000000 -2670.292480000000 -2229.202390000000 0.000000000000 0.000000000000 -11203.140600000001 -2670.292480000000 27007.533200000002 1196.832520000000 -4968.570800000000 11203.140600000001 0.000000000000 -2229.202390000000 1196.832520000000 26617.644499999999 6026.757810000000 2670.292480000000 2229.202390000000 0.000000000000 -4968.570800000000 6026.757810000000 3098.416750000000 14 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8581.081050000001 -300.231079000000 0.000000000000 5000.000000000000 0.000000000000 -8581.081050000001 0.000000000000 -2886.056400000000 0.000000000000 0.000000000000 5000.000000000000 300.231079000000 2886.056400000000 0.000000000000 0.000000000000 -8581.081050000001 300.231079000000 15164.535200000000 88.562561000000 5143.912110000000 8581.081050000001 0.000000000000 2886.056400000000 88.562561000000 17343.052700000000 -357.931061000000 -300.231079000000 -2886.056400000000 0.000000000000 5143.912110000000 -357.931061000000 2395.268550000000 15 19 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9706.034180000001 3137.244870000000 0.000000000000 5000.000000000000 0.000000000000 -9706.034180000001 0.000000000000 3521.222900000000 0.000000000000 0.000000000000 5000.000000000000 -3137.244870000000 -3521.222900000000 0.000000000000 0.000000000000 -9706.034180000001 -3137.244870000000 21363.169900000001 2241.612300000000 -6795.548340000000 9706.034180000001 0.000000000000 -3521.222900000000 2241.612300000000 21489.468799999999 6130.337400000000 3137.244870000000 3521.222900000000 0.000000000000 -6795.548340000000 6130.337400000000 5044.949710000000 15 22 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10409.199199999999 682.487183000000 0.000000000000 5000.000000000000 0.000000000000 -10409.199199999999 0.000000000000 -2637.217530000000 0.000000000000 0.000000000000 5000.000000000000 -682.487183000000 2637.217530000000 0.000000000000 0.000000000000 -10409.199199999999 -682.487183000000 23057.736300000000 -883.743958000000 6256.773930000000 10409.199199999999 0.000000000000 2637.217530000000 -883.743958000000 24982.185500000000 1970.102660000000 682.487183000000 -2637.217530000000 0.000000000000 6256.773930000000 1970.102660000000 3013.803960000000 15 23 60 1605.000000000000 0.000000000000 0.000000000000 0.000000000000 3618.205570000000 357.294281000000 0.000000000000 1605.000000000000 0.000000000000 -3618.205570000000 0.000000000000 -1540.343870000000 0.000000000000 0.000000000000 1605.000000000000 -357.294281000000 1540.343870000000 0.000000000000 0.000000000000 -3618.205570000000 -357.294281000000 8560.200199999999 -405.035278000000 3516.529790000000 3618.205570000000 0.000000000000 1540.343870000000 -405.035278000000 9792.097659999999 892.720154000000 357.294281000000 -1540.343870000000 0.000000000000 3516.529790000000 892.720154000000 1891.983640000000 16 22 60 4336.000000000000 0.000000000000 0.000000000000 0.000000000000 7936.187010000000 -1519.766480000000 0.000000000000 4336.000000000000 0.000000000000 -7936.187010000000 0.000000000000 -3027.092770000000 0.000000000000 0.000000000000 4336.000000000000 1519.766480000000 3027.092770000000 0.000000000000 0.000000000000 -7936.187010000000 1519.766480000000 15495.529300000000 952.445129000000 5818.909180000000 7936.187010000000 0.000000000000 3027.092770000000 952.445129000000 17605.353500000001 -2632.203610000000 -1519.766480000000 -3027.092770000000 0.000000000000 5818.909180000000 -2632.203610000000 3604.890630000000 17 19 60 3240.000000000000 0.000000000000 0.000000000000 0.000000000000 5966.093750000000 1328.052120000000 0.000000000000 3240.000000000000 0.000000000000 -5966.093750000000 0.000000000000 2160.486330000000 0.000000000000 0.000000000000 3240.000000000000 -1328.052120000000 -2160.486330000000 0.000000000000 0.000000000000 -5966.093750000000 -1328.052120000000 11660.157200000000 880.391174000000 -3975.202390000000 5966.093750000000 0.000000000000 -2160.486330000000 880.391174000000 12503.209999999999 2453.655760000000 1328.052120000000 2160.486330000000 0.000000000000 -3975.202390000000 2453.655760000000 2160.612790000000 17 20 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9889.599609999999 1920.392090000000 0.000000000000 5000.000000000000 0.000000000000 -9889.599609999999 0.000000000000 1000.172240000000 0.000000000000 0.000000000000 5000.000000000000 -1920.392090000000 -1000.172240000000 0.000000000000 0.000000000000 -9889.599609999999 -1920.392090000000 20688.423800000000 393.190002000000 -1855.681880000000 9889.599609999999 0.000000000000 -1000.172240000000 393.190002000000 20330.736300000000 3864.037350000000 1920.392090000000 1000.172240000000 0.000000000000 -1855.681880000000 3864.037350000000 1731.432860000000 17 23 60 2450.000000000000 0.000000000000 0.000000000000 0.000000000000 5303.174320000000 133.724365000000 0.000000000000 2450.000000000000 0.000000000000 -5303.174320000000 0.000000000000 -2185.551030000000 0.000000000000 0.000000000000 2450.000000000000 -133.724365000000 2185.551030000000 0.000000000000 0.000000000000 -5303.174320000000 -133.724365000000 11680.244100000000 -61.270298000000 4774.561520000000 5303.174320000000 0.000000000000 2185.551030000000 -61.270298000000 13614.259800000000 296.907990000000 133.724365000000 -2185.551030000000 0.000000000000 4774.561520000000 296.907990000000 2221.407470000000 18 22 60 4204.000000000000 0.000000000000 0.000000000000 0.000000000000 6997.552250000000 5.979236130000 0.000000000000 4204.000000000000 0.000000000000 -6997.552250000000 0.000000000000 -2275.545170000000 0.000000000000 0.000000000000 4204.000000000000 -5.979236130000 2275.545170000000 0.000000000000 0.000000000000 -6997.552250000000 -5.979236130000 12003.868200000001 -92.376495400000 3877.216800000000 6997.552250000000 0.000000000000 2275.545170000000 -92.376495400000 13265.139600000000 102.717934000000 5.979236130000 -2275.545170000000 0.000000000000 3877.216800000000 102.717934000000 1763.258790000000 19 21 60 509.000000000000 0.000000000000 0.000000000000 0.000000000000 572.718323000000 -31.206304600000 0.000000000000 509.000000000000 0.000000000000 -572.718323000000 0.000000000000 -315.395935000000 0.000000000000 0.000000000000 509.000000000000 31.206304600000 315.395935000000 0.000000000000 0.000000000000 -572.718323000000 31.206304600000 673.384888000000 10.316929800000 355.892548000000 572.718323000000 0.000000000000 315.395935000000 10.316929800000 847.517273000000 -30.883026100000 -31.206304600000 -315.395935000000 0.000000000000 355.892548000000 -30.883026100000 227.646118000000 20 22 60 659.000000000000 0.000000000000 0.000000000000 0.000000000000 802.047180000000 -325.155060000000 0.000000000000 659.000000000000 0.000000000000 -802.047180000000 0.000000000000 -527.167786000000 0.000000000000 0.000000000000 659.000000000000 325.155060000000 527.167786000000 0.000000000000 0.000000000000 -802.047180000000 325.155060000000 1155.267700000000 247.479294000000 653.320557000000 802.047180000000 0.000000000000 527.167786000000 247.479294000000 1443.042480000000 -388.090607000000 -325.155060000000 -527.167786000000 0.000000000000 653.320557000000 -388.090607000000 627.669373000000 21 23 60 3152.000000000000 0.000000000000 0.000000000000 0.000000000000 4897.454590000000 98.041168200000 0.000000000000 3152.000000000000 0.000000000000 -4897.454590000000 0.000000000000 -2994.012450000000 0.000000000000 0.000000000000 3152.000000000000 -98.041168200000 2994.012450000000 0.000000000000 0.000000000000 -4897.454590000000 -98.041168200000 7775.870120000000 -55.676048300000 4756.795900000000 4897.454590000000 0.000000000000 2994.012450000000 -55.676048300000 10766.949199999999 153.080765000000 98.041168200000 -2994.012450000000 0.000000000000 4756.795900000000 153.080765000000 3185.394290000000 22 31 60 2947.000000000000 0.000000000000 0.000000000000 0.000000000000 5463.673340000000 2677.382320000000 0.000000000000 2947.000000000000 0.000000000000 -5463.673340000000 0.000000000000 -2092.503910000000 0.000000000000 0.000000000000 2947.000000000000 -2677.382320000000 2092.503910000000 0.000000000000 0.000000000000 -5463.673340000000 -2677.382320000000 12784.274400000000 -1925.146240000000 3794.847410000000 5463.673340000000 0.000000000000 2092.503910000000 -1925.146240000000 12084.333000000001 4990.667970000000 2677.382320000000 -2092.503910000000 0.000000000000 3794.847410000000 4990.667970000000 4479.915040000000 22 32 60 2866.000000000000 0.000000000000 0.000000000000 0.000000000000 5325.100100000000 2536.616210000000 0.000000000000 2866.000000000000 0.000000000000 -5325.100100000000 0.000000000000 -1822.280150000000 0.000000000000 0.000000000000 2866.000000000000 -2536.616210000000 1822.280150000000 0.000000000000 0.000000000000 -5325.100100000000 -2536.616210000000 12421.960900000000 -1670.604370000000 3298.684810000000 5325.100100000000 0.000000000000 1822.280150000000 -1670.604370000000 11567.255900000000 4735.054200000000 2536.616210000000 -1822.280150000000 0.000000000000 3298.684810000000 4735.054200000000 4078.102540000000 22 42 60 2281.000000000000 0.000000000000 0.000000000000 0.000000000000 4119.906250000000 1951.700200000000 0.000000000000 2281.000000000000 0.000000000000 -4119.906250000000 0.000000000000 -1029.057740000000 0.000000000000 0.000000000000 2281.000000000000 -1951.700200000000 1029.057740000000 0.000000000000 0.000000000000 -4119.906250000000 -1951.700200000000 9242.460940000001 -1001.082520000000 1866.596800000000 4119.906250000000 0.000000000000 1029.057740000000 -1001.082520000000 8340.512699999999 3561.489750000000 1951.700200000000 -1029.057740000000 0.000000000000 1866.596800000000 3561.489750000000 2645.674320000000 22 43 60 2670.000000000000 0.000000000000 0.000000000000 0.000000000000 4166.969240000000 1629.465940000000 0.000000000000 2670.000000000000 0.000000000000 -4166.969240000000 0.000000000000 -1991.841310000000 0.000000000000 0.000000000000 2670.000000000000 -1629.465940000000 1991.841310000000 0.000000000000 0.000000000000 -4166.969240000000 -1629.465940000000 8268.956050000001 -1346.297850000000 3196.178220000000 4166.969240000000 0.000000000000 1991.841310000000 -1346.297850000000 8462.863280000000 2915.460450000000 1629.465940000000 -1991.841310000000 0.000000000000 3196.178220000000 2915.460450000000 3043.918460000000 23 24 60 4210.000000000000 0.000000000000 0.000000000000 0.000000000000 9012.604490000000 -1689.114990000000 0.000000000000 4210.000000000000 0.000000000000 -9012.604490000000 0.000000000000 -4649.792480000000 0.000000000000 0.000000000000 4210.000000000000 1689.114990000000 4649.792480000000 0.000000000000 0.000000000000 -9012.604490000000 1689.114990000000 20399.187500000000 1989.523680000000 10022.805700000001 9012.604490000000 0.000000000000 4649.792480000000 1989.523680000000 24840.359400000001 -3566.619870000000 -1689.114990000000 -4649.792480000000 0.000000000000 10022.805700000001 -3566.619870000000 6366.328610000000 23 30 60 1683.000000000000 0.000000000000 0.000000000000 0.000000000000 3851.267580000000 -97.438255300000 0.000000000000 1683.000000000000 0.000000000000 -3851.267580000000 0.000000000000 -1805.542720000000 0.000000000000 0.000000000000 1683.000000000000 97.438255300000 1805.542720000000 0.000000000000 0.000000000000 -3851.267580000000 97.438255300000 9003.508790000000 130.280212000000 4149.231930000000 3851.267580000000 0.000000000000 1805.542720000000 130.280212000000 10929.546899999999 -198.312744000000 -97.438255300000 -1805.542720000000 0.000000000000 4149.231930000000 -198.312744000000 2105.047850000000 23 43 60 4075.000000000000 0.000000000000 0.000000000000 0.000000000000 9534.489260000000 54.876522100000 0.000000000000 4075.000000000000 0.000000000000 -9534.489260000000 0.000000000000 -2167.363770000000 0.000000000000 0.000000000000 4075.000000000000 -54.876522100000 2167.363770000000 0.000000000000 0.000000000000 -9534.489260000000 -54.876522100000 23038.158200000002 -23.251194000000 5155.062990000000 9534.489260000000 0.000000000000 2167.363770000000 -23.251194000000 24633.808600000000 403.577515000000 54.876522100000 -2167.363770000000 0.000000000000 5155.062990000000 403.577515000000 2439.864010000000 23 44 60 3928.000000000000 0.000000000000 0.000000000000 0.000000000000 8534.425780000000 -379.730103000000 0.000000000000 3928.000000000000 0.000000000000 -8534.425780000000 0.000000000000 -1989.360600000000 0.000000000000 0.000000000000 3928.000000000000 379.730103000000 1989.360600000000 0.000000000000 0.000000000000 -8534.425780000000 379.730103000000 19904.468799999999 274.581055000000 4470.180660000000 8534.425780000000 0.000000000000 1989.360600000000 274.581055000000 21138.306600000000 -307.048737000000 -379.730103000000 -1989.360600000000 0.000000000000 4470.180660000000 -307.048737000000 2506.678470000000 23 45 60 3255.000000000000 0.000000000000 0.000000000000 0.000000000000 7063.051270000000 -264.666931000000 0.000000000000 3255.000000000000 0.000000000000 -7063.051270000000 0.000000000000 -1390.849370000000 0.000000000000 0.000000000000 3255.000000000000 264.666931000000 1390.849370000000 0.000000000000 0.000000000000 -7063.051270000000 264.666931000000 16434.777300000002 212.239487000000 3098.873050000000 7063.051270000000 0.000000000000 1390.849370000000 212.239487000000 17342.150399999999 -139.215210000000 -264.666931000000 -1390.849370000000 0.000000000000 3098.873050000000 -139.215210000000 1896.301030000000 23 46 60 4757.000000000000 0.000000000000 0.000000000000 0.000000000000 11105.174800000001 -108.365555000000 0.000000000000 4757.000000000000 0.000000000000 -11105.174800000001 0.000000000000 -3306.557620000000 0.000000000000 0.000000000000 4757.000000000000 108.365555000000 3306.557620000000 0.000000000000 0.000000000000 -11105.174800000001 108.365555000000 26789.904299999998 153.967560000000 7690.614260000000 11105.174800000001 0.000000000000 3306.557620000000 153.967560000000 29472.580099999999 91.858688400000 -108.365555000000 -3306.557620000000 0.000000000000 7690.614260000000 91.858688400000 3876.841800000000 23 47 60 2959.000000000000 0.000000000000 0.000000000000 0.000000000000 7205.481930000000 454.086975000000 0.000000000000 2959.000000000000 0.000000000000 -7205.481930000000 0.000000000000 -1602.857910000000 0.000000000000 0.000000000000 2959.000000000000 -454.086975000000 1602.857910000000 0.000000000000 0.000000000000 -7205.481930000000 -454.086975000000 17888.298800000000 -351.319366000000 3957.021000000000 7205.481930000000 0.000000000000 1602.857910000000 -351.319366000000 19233.074199999999 1223.962650000000 454.086975000000 -1602.857910000000 0.000000000000 3957.021000000000 1223.962650000000 1829.007320000000 24 27 60 3453.000000000000 0.000000000000 0.000000000000 0.000000000000 5894.151860000000 -302.828583000000 0.000000000000 3453.000000000000 0.000000000000 -5894.151860000000 0.000000000000 -4181.672850000000 0.000000000000 0.000000000000 3453.000000000000 302.828583000000 4181.672850000000 0.000000000000 0.000000000000 -5894.151860000000 302.828583000000 10684.404300000000 284.826080000000 7133.379880000000 5894.151860000000 0.000000000000 4181.672850000000 284.826080000000 15333.949199999999 -560.659363000000 -302.828583000000 -4181.672850000000 0.000000000000 7133.379880000000 -560.659363000000 5571.036620000000 24 32 60 3328.000000000000 0.000000000000 0.000000000000 0.000000000000 7754.746580000000 -465.116821000000 0.000000000000 3328.000000000000 0.000000000000 -7754.746580000000 0.000000000000 1062.190430000000 0.000000000000 0.000000000000 3328.000000000000 465.116821000000 -1062.190430000000 0.000000000000 0.000000000000 -7754.746580000000 465.116821000000 18521.052700000000 -88.365509000000 -2502.303220000000 7754.746580000000 0.000000000000 -1062.190430000000 -88.365509000000 18709.353500000001 -925.722168000000 -465.116821000000 1062.190430000000 0.000000000000 -2502.303220000000 -925.722168000000 686.025879000000 24 42 60 2318.000000000000 0.000000000000 0.000000000000 0.000000000000 5903.643070000000 -663.781006000000 0.000000000000 2318.000000000000 0.000000000000 -5903.643070000000 0.000000000000 441.449280000000 0.000000000000 0.000000000000 2318.000000000000 663.781006000000 -441.449280000000 0.000000000000 0.000000000000 -5903.643070000000 663.781006000000 15709.853499999999 -64.696517900000 -923.198547000000 5903.643070000000 0.000000000000 -441.449280000000 -64.696517900000 15802.506799999999 -1714.548340000000 -663.781006000000 441.449280000000 0.000000000000 -923.198547000000 -1714.548340000000 781.042908000000 24 43 60 2560.000000000000 0.000000000000 0.000000000000 0.000000000000 5863.811520000000 -984.063721000000 0.000000000000 2560.000000000000 0.000000000000 -5863.811520000000 0.000000000000 615.619324000000 0.000000000000 0.000000000000 2560.000000000000 984.063721000000 -615.619324000000 0.000000000000 0.000000000000 -5863.811520000000 984.063721000000 14201.405300000000 -210.622452000000 -1241.857060000000 5863.811520000000 0.000000000000 -615.619324000000 -210.622452000000 14226.124000000000 -2214.111820000000 -984.063721000000 615.619324000000 0.000000000000 -1241.857060000000 -2214.111820000000 1212.782590000000 24 44 60 2162.000000000000 0.000000000000 0.000000000000 0.000000000000 5081.215330000000 -972.032837000000 0.000000000000 2162.000000000000 0.000000000000 -5081.215330000000 0.000000000000 -100.640244000000 0.000000000000 0.000000000000 2162.000000000000 972.032837000000 100.640244000000 0.000000000000 0.000000000000 -5081.215330000000 972.032837000000 12720.049800000001 163.649612000000 306.713715000000 5081.215330000000 0.000000000000 100.640244000000 163.649612000000 12502.764600000000 -2241.723630000000 -972.032837000000 -100.640244000000 0.000000000000 306.713715000000 -2241.723630000000 1130.682130000000 24 45 60 1874.000000000000 0.000000000000 0.000000000000 0.000000000000 4328.558590000000 -767.866272000000 0.000000000000 1874.000000000000 0.000000000000 -4328.558590000000 0.000000000000 0.929252386000 0.000000000000 0.000000000000 1874.000000000000 767.866272000000 -0.929252386000 0.000000000000 0.000000000000 -4328.558590000000 767.866272000000 10615.372100000001 75.163986200000 88.658905000000 4328.558590000000 0.000000000000 -0.929252386000 75.163986200000 10606.557600000000 -1743.005130000000 -767.866272000000 0.929252386000 0.000000000000 88.658905000000 -1743.005130000000 1034.791260000000 24 46 60 3103.000000000000 0.000000000000 0.000000000000 0.000000000000 7095.149410000000 -1391.773930000000 0.000000000000 3103.000000000000 0.000000000000 -7095.149410000000 0.000000000000 467.478760000000 0.000000000000 0.000000000000 3103.000000000000 1391.773930000000 -467.478760000000 0.000000000000 0.000000000000 -7095.149410000000 1391.773930000000 17343.414100000002 -106.739082000000 -1014.630430000000 7095.149410000000 0.000000000000 -467.478760000000 -106.739082000000 16746.744100000000 -3037.962890000000 -1391.773930000000 467.478760000000 0.000000000000 -1014.630430000000 -3037.962890000000 1346.050170000000 24 47 60 2328.000000000000 0.000000000000 0.000000000000 0.000000000000 6399.823240000000 -745.861084000000 0.000000000000 2328.000000000000 0.000000000000 -6399.823240000000 0.000000000000 132.532532000000 0.000000000000 0.000000000000 2328.000000000000 745.861084000000 -132.532532000000 0.000000000000 0.000000000000 -6399.823240000000 745.861084000000 18374.730500000001 83.481468200000 -117.093414000000 6399.823240000000 0.000000000000 -132.532532000000 83.481468200000 18350.183600000000 -2113.755370000000 -745.861084000000 132.532532000000 0.000000000000 -117.093414000000 -2113.755370000000 739.148682000000 25 31 60 3065.000000000000 0.000000000000 0.000000000000 0.000000000000 8729.103520000001 -2063.344480000000 0.000000000000 3065.000000000000 0.000000000000 -8729.103520000001 0.000000000000 3525.192140000000 0.000000000000 0.000000000000 3065.000000000000 2063.344480000000 -3525.192140000000 0.000000000000 0.000000000000 -8729.103520000001 2063.344480000000 26585.636699999999 -2339.251710000000 -10180.054700000001 8729.103520000001 0.000000000000 -3525.192140000000 -2339.251710000000 29356.677700000000 -5802.952150000000 -2063.344480000000 3525.192140000000 0.000000000000 -10180.054700000001 -5802.952150000000 5611.658690000000 26 30 60 4017.000000000000 0.000000000000 0.000000000000 0.000000000000 10678.755900000000 -802.096497000000 0.000000000000 4017.000000000000 0.000000000000 -10678.755900000000 0.000000000000 4115.131840000000 0.000000000000 0.000000000000 4017.000000000000 802.096497000000 -4115.131840000000 0.000000000000 0.000000000000 -10678.755900000000 802.096497000000 29602.894499999999 -1069.256100000000 -11369.543900000001 10678.755900000000 0.000000000000 -4115.131840000000 -1069.256100000000 33710.746099999997 -2430.985350000000 -802.096497000000 4115.131840000000 0.000000000000 -11369.543900000001 -2430.985350000000 5100.363280000000 27 29 60 2161.000000000000 0.000000000000 0.000000000000 0.000000000000 4086.232180000000 -674.621216000000 0.000000000000 2161.000000000000 0.000000000000 -4086.232180000000 0.000000000000 1322.706420000000 0.000000000000 0.000000000000 2161.000000000000 674.621216000000 -1322.706420000000 0.000000000000 0.000000000000 -4086.232180000000 674.621216000000 8067.996090000000 -377.164520000000 -2542.937500000000 4086.232180000000 0.000000000000 -1322.706420000000 -377.164520000000 8682.602540000000 -1230.699220000000 -674.621216000000 1322.706420000000 0.000000000000 -2542.937500000000 -1230.699220000000 1189.151490000000 28 30 60 1484.000000000000 0.000000000000 0.000000000000 0.000000000000 3055.883790000000 -85.501617400000 0.000000000000 1484.000000000000 0.000000000000 -3055.883790000000 0.000000000000 1667.543090000000 0.000000000000 0.000000000000 1484.000000000000 85.501617400000 -1667.543090000000 0.000000000000 0.000000000000 -3055.883790000000 85.501617400000 6426.886720000000 -116.127083000000 -3420.495850000000 3055.883790000000 0.000000000000 -1667.543090000000 -116.127083000000 8250.495120000000 -190.719421000000 -85.501617400000 1667.543090000000 0.000000000000 -3420.495850000000 -190.719421000000 2016.419310000000 29 32 60 4895.000000000000 0.000000000000 0.000000000000 0.000000000000 10185.639600000000 1572.052120000000 0.000000000000 4895.000000000000 0.000000000000 -10185.639600000000 0.000000000000 4706.737300000000 0.000000000000 0.000000000000 4895.000000000000 -1572.052120000000 -4706.737300000000 0.000000000000 0.000000000000 -10185.639600000000 -1572.052120000000 22811.980500000001 1727.440060000000 -9958.046880000000 10185.639600000000 0.000000000000 -4706.737300000000 1727.440060000000 26554.767599999999 3746.172850000000 1572.052120000000 4706.737300000000 0.000000000000 -9958.046880000000 3746.172850000000 5842.717770000000 29 42 60 1967.000000000000 0.000000000000 0.000000000000 0.000000000000 4833.109860000000 794.443726000000 0.000000000000 1967.000000000000 0.000000000000 -4833.109860000000 0.000000000000 1592.181400000000 0.000000000000 0.000000000000 1967.000000000000 -794.443726000000 -1592.181400000000 0.000000000000 0.000000000000 -4833.109860000000 -794.443726000000 12867.324199999999 772.910889000000 -3957.794430000000 4833.109860000000 0.000000000000 -1592.181400000000 772.910889000000 13797.087900000000 2108.380370000000 794.443726000000 1592.181400000000 0.000000000000 -3957.794430000000 2108.380370000000 2094.572510000000 29 43 60 2425.000000000000 0.000000000000 0.000000000000 0.000000000000 5003.741700000000 258.411896000000 0.000000000000 2425.000000000000 0.000000000000 -5003.741700000000 0.000000000000 1750.188720000000 0.000000000000 0.000000000000 2425.000000000000 -258.411896000000 -1750.188720000000 0.000000000000 0.000000000000 -5003.741700000000 -258.411896000000 10975.052700000000 187.334732000000 -3521.248050000000 5003.741700000000 0.000000000000 -1750.188720000000 187.334732000000 12231.197300000000 687.023193000000 258.411896000000 1750.188720000000 0.000000000000 -3521.248050000000 687.023193000000 1916.512820000000 29 44 60 3515.000000000000 0.000000000000 0.000000000000 0.000000000000 6834.867680000000 -376.907501000000 0.000000000000 3515.000000000000 0.000000000000 -6834.867680000000 0.000000000000 1784.561160000000 0.000000000000 0.000000000000 3515.000000000000 376.907501000000 -1784.561160000000 0.000000000000 0.000000000000 -6834.867680000000 376.907501000000 14555.025400000000 -68.279182400000 -3310.244380000000 6834.867680000000 0.000000000000 -1784.561160000000 -68.279182400000 15374.085900000000 -437.360229000000 -376.907501000000 1784.561160000000 0.000000000000 -3310.244380000000 -437.360229000000 1826.806400000000 29 45 60 2328.000000000000 0.000000000000 0.000000000000 0.000000000000 4585.935550000000 60.926750200000 0.000000000000 2328.000000000000 0.000000000000 -4585.935550000000 0.000000000000 1222.929440000000 0.000000000000 0.000000000000 2328.000000000000 -60.926750200000 -1222.929440000000 0.000000000000 0.000000000000 -4585.935550000000 -60.926750200000 9950.212890000001 71.390899700000 -2265.382810000000 4585.935550000000 0.000000000000 -1222.929440000000 71.390899700000 10648.929700000001 341.246490000000 60.926750200000 1222.929440000000 0.000000000000 -2265.382810000000 341.246490000000 1341.850830000000 29 46 60 2631.000000000000 0.000000000000 0.000000000000 0.000000000000 5709.300780000000 232.706406000000 0.000000000000 2631.000000000000 0.000000000000 -5709.300780000000 0.000000000000 1754.739010000000 0.000000000000 0.000000000000 2631.000000000000 -232.706406000000 -1754.739010000000 0.000000000000 0.000000000000 -5709.300780000000 -232.706406000000 12988.972700000000 317.498840000000 -3819.638180000000 5709.300780000000 0.000000000000 -1754.739010000000 317.498840000000 13901.169900000001 653.239990000000 232.706406000000 1754.739010000000 0.000000000000 -3819.638180000000 653.239990000000 1803.478880000000 29 47 60 2836.000000000000 0.000000000000 0.000000000000 0.000000000000 8065.125000000000 1434.091430000000 0.000000000000 2836.000000000000 0.000000000000 -8065.125000000000 0.000000000000 2396.634280000000 0.000000000000 0.000000000000 2836.000000000000 -1434.091430000000 -2396.634280000000 0.000000000000 0.000000000000 -8065.125000000000 -1434.091430000000 24884.435500000000 1573.976930000000 -6904.501950000000 8065.125000000000 0.000000000000 -2396.634280000000 1573.976930000000 26089.099600000001 4325.117190000000 1434.091430000000 2396.634280000000 0.000000000000 -6904.501950000000 4325.117190000000 3591.401370000000 30 33 60 4267.000000000000 0.000000000000 0.000000000000 0.000000000000 13266.405300000000 -1109.483280000000 0.000000000000 4267.000000000000 0.000000000000 -13266.405300000000 0.000000000000 3683.573000000000 0.000000000000 0.000000000000 4267.000000000000 1109.483280000000 -3683.573000000000 0.000000000000 0.000000000000 -13266.405300000000 1109.483280000000 43184.625000000000 -761.636353000000 -11527.031300000001 13266.405300000000 0.000000000000 -3683.573000000000 -761.636353000000 45856.332000000002 -3428.702390000000 -1109.483280000000 3683.573000000000 0.000000000000 -11527.031300000001 -3428.702390000000 4204.443360000000 30 34 60 1487.000000000000 0.000000000000 0.000000000000 0.000000000000 5050.472660000000 59.273216200000 0.000000000000 1487.000000000000 0.000000000000 -5050.472660000000 0.000000000000 1363.702760000000 0.000000000000 0.000000000000 1487.000000000000 -59.273216200000 -1363.702760000000 0.000000000000 0.000000000000 -5050.472660000000 -59.273216200000 17184.054700000001 44.399089800000 -4623.701660000000 5050.472660000000 0.000000000000 -1363.702760000000 44.399089800000 18455.427700000000 197.960922000000 59.273216200000 1363.702760000000 0.000000000000 -4623.701660000000 197.960922000000 1320.224370000000 30 36 60 1179.000000000000 0.000000000000 0.000000000000 0.000000000000 3996.296880000000 28.325080900000 0.000000000000 1179.000000000000 0.000000000000 -3996.296880000000 0.000000000000 1158.330570000000 0.000000000000 0.000000000000 1179.000000000000 -28.325080900000 -1158.330570000000 0.000000000000 0.000000000000 -3996.296880000000 -28.325080900000 13566.613300000001 23.466472600000 -3920.416990000000 3996.296880000000 0.000000000000 -1158.330570000000 23.466472600000 14729.981400000001 93.184112500000 28.325080900000 1158.330570000000 0.000000000000 -3920.416990000000 93.184112500000 1194.380250000000 30 41 60 1235.000000000000 0.000000000000 0.000000000000 0.000000000000 4064.569340000000 -194.727753000000 0.000000000000 1235.000000000000 0.000000000000 -4064.569340000000 0.000000000000 1152.158080000000 0.000000000000 0.000000000000 1235.000000000000 194.727753000000 -1152.158080000000 0.000000000000 0.000000000000 -4064.569340000000 194.727753000000 13664.442400000000 -170.640137000000 -3791.015870000000 4064.569340000000 0.000000000000 -1152.158080000000 -170.640137000000 14632.196300000000 -645.061584000000 -194.727753000000 1152.158080000000 0.000000000000 -3791.015870000000 -645.061584000000 1269.127690000000 30 42 60 2986.000000000000 0.000000000000 0.000000000000 0.000000000000 7874.777340000000 -1511.566890000000 0.000000000000 2986.000000000000 0.000000000000 -7874.777340000000 0.000000000000 1741.216430000000 0.000000000000 0.000000000000 2986.000000000000 1511.566890000000 -1741.216430000000 0.000000000000 0.000000000000 -7874.777340000000 1511.566890000000 22823.091799999998 -649.115540000000 -4851.448240000000 7874.777340000000 0.000000000000 -1741.216430000000 -649.115540000000 22973.562500000000 -3785.476070000000 -1511.566890000000 1741.216430000000 0.000000000000 -4851.448240000000 -3785.476070000000 2475.120360000000 30 46 60 1523.000000000000 0.000000000000 0.000000000000 0.000000000000 3820.407710000000 -377.813416000000 0.000000000000 1523.000000000000 0.000000000000 -3820.407710000000 0.000000000000 1144.788570000000 0.000000000000 0.000000000000 1523.000000000000 377.813416000000 -1144.788570000000 0.000000000000 0.000000000000 -3820.407710000000 377.813416000000 10447.388700000000 -198.510010000000 -3156.052730000000 3820.407710000000 0.000000000000 -1144.788570000000 -198.510010000000 11328.775400000000 -750.834900000000 -377.813416000000 1144.788570000000 0.000000000000 -3156.052730000000 -750.834900000000 1233.458500000000 30 48 60 4265.000000000000 0.000000000000 0.000000000000 0.000000000000 13629.639600000000 -2201.549320000000 0.000000000000 4265.000000000000 0.000000000000 -13629.639600000000 0.000000000000 2789.211910000000 0.000000000000 0.000000000000 4265.000000000000 2201.549320000000 -2789.211910000000 0.000000000000 0.000000000000 -13629.639600000000 2201.549320000000 45386.480499999998 -1022.502260000000 -9027.824220000000 13629.639600000000 0.000000000000 -2789.211910000000 -1022.502260000000 46082.207000000002 -6859.444820000000 -2201.549320000000 2789.211910000000 0.000000000000 -9027.824220000000 -6859.444820000000 4007.064210000000 31 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15427.063500000000 4033.050540000000 0.000000000000 5000.000000000000 0.000000000000 -15427.063500000000 0.000000000000 -4555.022950000000 0.000000000000 0.000000000000 5000.000000000000 -4033.050540000000 4555.022950000000 0.000000000000 0.000000000000 -15427.063500000000 -4033.050540000000 51295.429700000001 -3712.675290000000 14308.052700000000 15427.063500000000 0.000000000000 4555.022950000000 -3712.675290000000 52668.164100000002 12447.231400000001 4033.050540000000 -4555.022950000000 0.000000000000 14308.052700000000 12447.231400000001 8378.819340000000 31 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15445.470700000000 4165.003420000000 0.000000000000 5000.000000000000 0.000000000000 -15445.470700000000 0.000000000000 -2965.501460000000 0.000000000000 0.000000000000 5000.000000000000 -4165.003420000000 2965.501460000000 0.000000000000 0.000000000000 -15445.470700000000 -4165.003420000000 51603.652300000002 -2441.302490000000 9182.383790000000 15445.470700000000 0.000000000000 2965.501460000000 -2441.302490000000 50784.289100000002 12874.451200000000 4165.003420000000 -2965.501460000000 0.000000000000 9182.383790000000 12874.451200000000 6597.342290000000 31 38 60 4762.000000000000 0.000000000000 0.000000000000 0.000000000000 14864.825199999999 4496.254880000000 0.000000000000 4762.000000000000 0.000000000000 -14864.825199999999 0.000000000000 -310.196381000000 0.000000000000 0.000000000000 4762.000000000000 -4496.254880000000 310.196381000000 0.000000000000 0.000000000000 -14864.825199999999 -4496.254880000000 50931.898399999998 -327.306885000000 903.153198000000 14864.825199999999 0.000000000000 310.196381000000 -327.306885000000 47073.664100000002 14117.255900000000 4496.254880000000 -310.196381000000 0.000000000000 903.153198000000 14117.255900000000 4842.152830000000 31 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14652.377000000000 3358.136720000000 0.000000000000 5000.000000000000 0.000000000000 -14652.377000000000 0.000000000000 -1284.725830000000 0.000000000000 0.000000000000 5000.000000000000 -3358.136720000000 1284.725830000000 0.000000000000 0.000000000000 -14652.377000000000 -3358.136720000000 46115.468800000002 -960.820557000000 4053.480220000000 14652.377000000000 0.000000000000 1284.725830000000 -960.820557000000 44820.906300000002 9929.769530000000 3358.136720000000 -1284.725830000000 0.000000000000 4053.480220000000 9929.769530000000 3861.025880000000 31 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11520.394500000000 257.167419000000 0.000000000000 5000.000000000000 0.000000000000 -11520.394500000000 0.000000000000 -131.793320000000 0.000000000000 0.000000000000 5000.000000000000 -257.167419000000 131.793320000000 0.000000000000 0.000000000000 -11520.394500000000 -257.167419000000 29525.490200000000 -238.898193000000 1474.822750000000 11520.394500000000 0.000000000000 131.793320000000 -238.898193000000 30294.894499999999 1526.579590000000 257.167419000000 -131.793320000000 0.000000000000 1474.822750000000 1526.579590000000 2766.859620000000 31 46 60 3429.000000000000 0.000000000000 0.000000000000 0.000000000000 6792.525880000000 156.781616000000 0.000000000000 3429.000000000000 0.000000000000 -6792.525880000000 0.000000000000 993.163818000000 0.000000000000 0.000000000000 3429.000000000000 -156.781616000000 -993.163818000000 0.000000000000 0.000000000000 -6792.525880000000 -156.781616000000 15482.967800000000 -277.689575000000 -1505.330200000000 6792.525880000000 0.000000000000 -993.163818000000 -277.689575000000 15877.617200000001 1162.097900000000 156.781616000000 993.163818000000 0.000000000000 -1505.330200000000 1162.097900000000 1825.531740000000 31 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15947.034200000000 3033.541750000000 0.000000000000 5000.000000000000 0.000000000000 -15947.034200000000 0.000000000000 -5367.141110000000 0.000000000000 0.000000000000 5000.000000000000 -3033.541750000000 5367.141110000000 0.000000000000 0.000000000000 -15947.034200000000 -3033.541750000000 53314.398399999998 -3295.074460000000 17182.375000000000 15947.034200000000 0.000000000000 5367.141110000000 -3295.074460000000 57071.457000000002 9569.510740000000 3033.541750000000 -5367.141110000000 0.000000000000 17182.375000000000 9569.510740000000 8351.995120000000 32 34 60 3457.000000000000 0.000000000000 0.000000000000 0.000000000000 9692.117190000001 3391.121340000000 0.000000000000 3457.000000000000 0.000000000000 -9692.117190000001 0.000000000000 -4465.091800000000 0.000000000000 0.000000000000 3457.000000000000 -3391.121340000000 4465.091800000000 0.000000000000 0.000000000000 -9692.117190000001 -3391.121340000000 30767.791000000001 -4383.228520000000 12498.241200000000 9692.117190000001 0.000000000000 4465.091800000000 -4383.228520000000 33111.375000000000 9528.030269999999 3391.121340000000 -4465.091800000000 0.000000000000 12498.241200000000 9528.030269999999 9294.298830000000 32 36 60 3470.000000000000 0.000000000000 0.000000000000 0.000000000000 9764.537109999999 3556.222170000000 0.000000000000 3470.000000000000 0.000000000000 -9764.537109999999 0.000000000000 -4510.057130000000 0.000000000000 0.000000000000 3470.000000000000 -3556.222170000000 4510.057130000000 0.000000000000 0.000000000000 -9764.537109999999 -3556.222170000000 31411.828099999999 -4624.640630000000 12674.584000000001 9764.537109999999 0.000000000000 4510.057130000000 -4624.640630000000 33521.640599999999 10050.036099999999 3556.222170000000 -4510.057130000000 0.000000000000 12674.584000000001 10050.036099999999 9710.243160000000 32 37 60 2624.000000000000 0.000000000000 0.000000000000 0.000000000000 7437.249510000000 2838.418950000000 0.000000000000 2624.000000000000 0.000000000000 -7437.249510000000 0.000000000000 -3497.611570000000 0.000000000000 0.000000000000 2624.000000000000 -2838.418950000000 3497.611570000000 0.000000000000 0.000000000000 -7437.249510000000 -2838.418950000000 24390.871100000000 -3786.968750000000 9899.358399999999 7437.249510000000 0.000000000000 3497.611570000000 -3786.968750000000 25868.429700000001 8111.129880000000 2838.418950000000 -3497.611570000000 0.000000000000 9899.358399999999 8111.129880000000 7905.351560000000 32 38 60 3189.000000000000 0.000000000000 0.000000000000 0.000000000000 9061.682620000000 3571.614260000000 0.000000000000 3189.000000000000 0.000000000000 -9061.682620000000 0.000000000000 -3922.651610000000 0.000000000000 0.000000000000 3189.000000000000 -3571.614260000000 3922.651610000000 0.000000000000 0.000000000000 -9061.682620000000 -3571.614260000000 29990.956999999999 -4397.916500000000 11118.122100000001 9061.682620000000 0.000000000000 3922.651610000000 -4397.916500000000 30804.005900000000 10218.183600000000 3571.614260000000 -3922.651610000000 0.000000000000 11118.122100000001 10218.183600000000 9060.693359999999 32 39 60 3601.000000000000 0.000000000000 0.000000000000 0.000000000000 10215.866200000000 3815.392330000000 0.000000000000 3601.000000000000 0.000000000000 -10215.866200000000 0.000000000000 -4231.665530000000 0.000000000000 0.000000000000 3601.000000000000 -3815.392330000000 4231.665530000000 0.000000000000 0.000000000000 -10215.866200000000 -3815.392330000000 33263.210899999998 -4458.582520000000 11948.024400000000 10215.866200000000 0.000000000000 4231.665530000000 -4458.582520000000 34271.125000000000 10852.212900000000 3815.392330000000 -4231.665530000000 0.000000000000 11948.024400000000 10852.212900000000 9337.675780000000 32 40 60 4288.000000000000 0.000000000000 0.000000000000 0.000000000000 12261.396500000001 2903.185790000000 0.000000000000 4288.000000000000 0.000000000000 -12261.396500000001 0.000000000000 -571.212830000000 0.000000000000 0.000000000000 4288.000000000000 -2903.185790000000 571.212830000000 0.000000000000 0.000000000000 -12261.396500000001 -2903.185790000000 38147.726600000002 -1574.051150000000 886.785706000000 12261.396500000001 0.000000000000 571.212830000000 -1574.051150000000 40810.164100000002 8228.291020000001 2903.185790000000 -571.212830000000 0.000000000000 886.785706000000 8228.291020000001 7454.505370000000 32 41 60 4380.000000000000 0.000000000000 0.000000000000 0.000000000000 11969.021500000001 3713.675290000000 0.000000000000 4380.000000000000 0.000000000000 -11969.021500000001 0.000000000000 -2352.762210000000 0.000000000000 0.000000000000 4380.000000000000 -3713.675290000000 2352.762210000000 0.000000000000 0.000000000000 -11969.021500000001 -3713.675290000000 36602.597699999998 -2697.626710000000 6659.681640000000 11969.021500000001 0.000000000000 2352.762210000000 -2697.626710000000 39090.382799999999 10297.268599999999 3713.675290000000 -2352.762210000000 0.000000000000 6659.681640000000 10297.268599999999 9588.524410000000 32 43 60 2638.000000000000 0.000000000000 0.000000000000 0.000000000000 4761.083010000000 0.425178289000 0.000000000000 2638.000000000000 0.000000000000 -4761.083010000000 0.000000000000 -360.224518000000 0.000000000000 0.000000000000 2638.000000000000 -0.425178289000 360.224518000000 0.000000000000 0.000000000000 -4761.083010000000 -0.425178289000 8975.130859999999 70.794349700000 573.002747000000 4761.083010000000 0.000000000000 360.224518000000 70.794349700000 9289.680660000000 96.999107400000 0.425178289000 -360.224518000000 0.000000000000 573.002747000000 96.999107400000 892.885437000000 32 44 60 2854.000000000000 0.000000000000 0.000000000000 0.000000000000 5212.329100000000 188.409897000000 0.000000000000 2854.000000000000 0.000000000000 -5212.329100000000 0.000000000000 -191.926331000000 0.000000000000 0.000000000000 2854.000000000000 -188.409897000000 191.926331000000 0.000000000000 0.000000000000 -5212.329100000000 -188.409897000000 9970.603520000001 -0.195706099000 281.643494000000 5212.329100000000 0.000000000000 191.926331000000 -0.195706099000 10151.989299999999 467.769043000000 188.409897000000 -191.926331000000 0.000000000000 281.643494000000 467.769043000000 911.910706000000 32 45 60 2559.000000000000 0.000000000000 0.000000000000 0.000000000000 4745.730470000000 353.896851000000 0.000000000000 2559.000000000000 0.000000000000 -4745.730470000000 0.000000000000 -150.418213000000 0.000000000000 0.000000000000 2559.000000000000 -353.896851000000 150.418213000000 0.000000000000 0.000000000000 -4745.730470000000 -353.896851000000 9272.306640000001 20.424408000000 206.587570000000 4745.730470000000 0.000000000000 150.418213000000 20.424408000000 9382.270510000000 777.767151000000 353.896851000000 -150.418213000000 0.000000000000 206.587570000000 777.767151000000 888.315308000000 32 46 60 3665.000000000000 0.000000000000 0.000000000000 0.000000000000 7635.396970000000 1000.844910000000 0.000000000000 3665.000000000000 0.000000000000 -7635.396970000000 0.000000000000 -1785.321290000000 0.000000000000 0.000000000000 3665.000000000000 -1000.844910000000 1785.321290000000 0.000000000000 0.000000000000 -7635.396970000000 -1000.844910000000 17867.773399999998 -1173.036740000000 4350.941890000000 7635.396970000000 0.000000000000 1785.321290000000 -1173.036740000000 19051.304700000001 2816.108150000000 1000.844910000000 -1785.321290000000 0.000000000000 4350.941890000000 2816.108150000000 3396.486080000000 32 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11931.367200000001 1709.747190000000 0.000000000000 5000.000000000000 0.000000000000 -11931.367200000001 0.000000000000 -4456.385740000000 0.000000000000 0.000000000000 5000.000000000000 -1709.747190000000 4456.385740000000 0.000000000000 0.000000000000 -11931.367200000001 -1709.747190000000 31438.054700000001 -1998.403080000000 11608.531300000001 11931.367200000001 0.000000000000 4456.385740000000 -1998.403080000000 35612.984400000001 4900.353520000000 1709.747190000000 -4456.385740000000 0.000000000000 11608.531300000001 4900.353520000000 7962.405760000000 32 48 60 3599.000000000000 0.000000000000 0.000000000000 0.000000000000 9874.718750000000 2207.794920000000 0.000000000000 3599.000000000000 0.000000000000 -9874.718750000000 0.000000000000 -4487.114750000000 0.000000000000 0.000000000000 3599.000000000000 -2207.794920000000 4487.114750000000 0.000000000000 0.000000000000 -9874.718750000000 -2207.794920000000 29546.119100000000 -2642.892580000000 12251.594700000000 9874.718750000000 0.000000000000 4487.114750000000 -2642.892580000000 33028.562500000000 6376.721190000000 2207.794920000000 -4487.114750000000 0.000000000000 12251.594700000000 6376.721190000000 7936.576170000000 33 35 60 3353.000000000000 0.000000000000 0.000000000000 0.000000000000 8800.807620000000 639.499084000000 0.000000000000 3353.000000000000 0.000000000000 -8800.807620000000 0.000000000000 -3852.306640000000 0.000000000000 0.000000000000 3353.000000000000 -639.499084000000 3852.306640000000 0.000000000000 0.000000000000 -8800.807620000000 -639.499084000000 23649.634800000000 -768.945923000000 10172.460900000000 8800.807620000000 0.000000000000 3852.306640000000 -768.945923000000 27918.787100000001 1828.177120000000 639.499084000000 -3852.306640000000 0.000000000000 10172.460900000000 1828.177120000000 4863.437500000000 33 46 60 3520.000000000000 0.000000000000 0.000000000000 0.000000000000 9256.832030000000 -1470.483640000000 0.000000000000 3520.000000000000 0.000000000000 -9256.832030000000 0.000000000000 267.040314000000 0.000000000000 0.000000000000 3520.000000000000 1470.483640000000 -267.040314000000 0.000000000000 0.000000000000 -9256.832030000000 1470.483640000000 25975.283200000002 -313.549927000000 -996.504028000000 9256.832030000000 0.000000000000 -267.040314000000 -313.549927000000 26201.179700000001 -4019.509280000000 -1470.483640000000 267.040314000000 0.000000000000 -996.504028000000 -4019.509280000000 1780.976320000000 33 49 60 2020.000000000000 0.000000000000 0.000000000000 0.000000000000 5369.815920000000 -64.682846100000 0.000000000000 2020.000000000000 0.000000000000 -5369.815920000000 0.000000000000 -2620.186280000000 0.000000000000 0.000000000000 2020.000000000000 64.682846100000 2620.186280000000 0.000000000000 0.000000000000 -5369.815920000000 64.682846100000 14692.971700000000 91.250076300000 6923.865230000000 5369.815920000000 0.000000000000 2620.186280000000 91.250076300000 17856.591799999998 -134.835846000000 -64.682846100000 -2620.186280000000 0.000000000000 6923.865230000000 -134.835846000000 3716.309080000000 34 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14774.962900000000 2402.671390000000 0.000000000000 5000.000000000000 0.000000000000 -14774.962900000000 0.000000000000 3364.833500000000 0.000000000000 0.000000000000 5000.000000000000 -2402.671390000000 -3364.833500000000 0.000000000000 0.000000000000 -14774.962900000000 -2402.671390000000 47401.304700000001 2052.303710000000 -10237.618200000001 14774.962900000000 0.000000000000 -3364.833500000000 2052.303710000000 47896.027300000002 8037.261720000000 2402.671390000000 3364.833500000000 0.000000000000 -10237.618200000001 8037.261720000000 5181.533690000000 34 41 60 4954.000000000000 0.000000000000 0.000000000000 0.000000000000 9865.166990000000 -1494.023440000000 0.000000000000 4954.000000000000 0.000000000000 -9865.166990000000 0.000000000000 2077.714110000000 0.000000000000 0.000000000000 4954.000000000000 1494.023440000000 -2077.714110000000 0.000000000000 0.000000000000 -9865.166990000000 1494.023440000000 20530.396499999999 -553.306213000000 -4207.468750000000 9865.166990000000 0.000000000000 -2077.714110000000 -553.306213000000 21159.982400000001 -2958.919680000000 -1494.023440000000 2077.714110000000 0.000000000000 -4207.468750000000 -2958.919680000000 2057.652590000000 34 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10121.744100000000 -2099.864500000000 0.000000000000 5000.000000000000 0.000000000000 -10121.744100000000 0.000000000000 1021.213130000000 0.000000000000 0.000000000000 5000.000000000000 2099.864500000000 -1021.213130000000 0.000000000000 0.000000000000 -10121.744100000000 2099.864500000000 21948.718799999999 -505.299805000000 -2066.953370000000 10121.744100000000 0.000000000000 -1021.213130000000 -505.299805000000 21601.181600000000 -4411.899900000000 -2099.864500000000 1021.213130000000 0.000000000000 -2066.953370000000 -4411.899900000000 2070.876220000000 34 51 60 2878.000000000000 0.000000000000 0.000000000000 0.000000000000 8417.901370000000 1164.433350000000 0.000000000000 2878.000000000000 0.000000000000 -8417.901370000000 0.000000000000 -1698.295530000000 0.000000000000 0.000000000000 2878.000000000000 -1164.433350000000 1698.295530000000 0.000000000000 0.000000000000 -8417.901370000000 -1164.433350000000 27184.265599999999 391.278961000000 4284.645510000000 8417.901370000000 0.000000000000 1698.295530000000 391.278961000000 27442.808600000000 4064.017330000000 1164.433350000000 -1698.295530000000 0.000000000000 4284.645510000000 4064.017330000000 4106.526860000000 34 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13936.188500000000 -787.242493000000 0.000000000000 5000.000000000000 0.000000000000 -13936.188500000000 0.000000000000 -6080.375490000000 0.000000000000 0.000000000000 5000.000000000000 787.242493000000 6080.375490000000 0.000000000000 0.000000000000 -13936.188500000000 787.242493000000 40768.117200000001 972.181152000000 17164.572300000000 13936.188500000000 0.000000000000 6080.375490000000 972.181152000000 47483.761700000003 -1882.961430000000 -787.242493000000 -6080.375490000000 0.000000000000 17164.572300000000 -1882.961430000000 9162.010740000000 35 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12038.388700000000 -3747.273930000000 0.000000000000 5000.000000000000 0.000000000000 -12038.388700000000 0.000000000000 2934.954100000000 0.000000000000 0.000000000000 5000.000000000000 3747.273930000000 -2934.954100000000 0.000000000000 0.000000000000 -12038.388700000000 3747.273930000000 33828.898399999998 -1601.283810000000 -7030.427250000000 12038.388700000000 0.000000000000 -2934.954100000000 -1601.283810000000 33483.535199999998 -8858.677729999999 -3747.273930000000 2934.954100000000 0.000000000000 -7030.427250000000 -8858.677729999999 6318.845210000000 35 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11623.562500000000 -3229.983890000000 0.000000000000 5000.000000000000 0.000000000000 -11623.562500000000 0.000000000000 3826.817380000000 0.000000000000 0.000000000000 5000.000000000000 3229.983890000000 -3826.817380000000 0.000000000000 0.000000000000 -11623.562500000000 3229.983890000000 31179.988300000001 -2098.374510000000 -9058.678710000000 11623.562500000000 0.000000000000 -3826.817380000000 -2098.374510000000 32447.052700000000 -7298.799320000000 -3229.983890000000 3826.817380000000 0.000000000000 -9058.678710000000 -7298.799320000000 6110.908200000000 35 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10786.083000000001 -3878.654540000000 0.000000000000 5000.000000000000 0.000000000000 -10786.083000000001 0.000000000000 2464.081540000000 0.000000000000 0.000000000000 5000.000000000000 3878.654540000000 -2464.081540000000 0.000000000000 0.000000000000 -10786.083000000001 3878.654540000000 27660.456999999999 -1536.941530000000 -5190.568850000000 10786.083000000001 0.000000000000 -2464.081540000000 -1536.941530000000 26357.281299999999 -8323.641600000001 -3878.654540000000 2464.081540000000 0.000000000000 -5190.568850000000 -8323.641600000001 5551.691410000000 35 51 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14661.631799999999 -849.489868000000 0.000000000000 5000.000000000000 0.000000000000 -14661.631799999999 0.000000000000 -827.522583000000 0.000000000000 0.000000000000 5000.000000000000 849.489868000000 827.522583000000 0.000000000000 0.000000000000 -14661.631799999999 849.489868000000 45115.589800000002 787.388794000000 1203.404910000000 14661.631799999999 0.000000000000 827.522583000000 787.388794000000 49175.500000000000 -2037.690550000000 -849.489868000000 -827.522583000000 0.000000000000 1203.404910000000 -2037.690550000000 7046.859860000000 35 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13753.303700000000 -840.850403000000 0.000000000000 5000.000000000000 0.000000000000 -13753.303700000000 0.000000000000 -4802.940920000000 0.000000000000 0.000000000000 5000.000000000000 840.850403000000 4802.940920000000 0.000000000000 0.000000000000 -13753.303700000000 840.850403000000 38757.710899999998 810.519836000000 13269.423800000000 13753.303700000000 0.000000000000 4802.940920000000 810.519836000000 43255.218800000002 -2252.088380000000 -840.850403000000 -4802.940920000000 0.000000000000 13269.423800000000 -2252.088380000000 5620.120610000000 35 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13904.345700000000 -2762.573240000000 0.000000000000 5000.000000000000 0.000000000000 -13904.345700000000 0.000000000000 -3720.011960000000 0.000000000000 0.000000000000 5000.000000000000 2762.573240000000 3720.011960000000 0.000000000000 0.000000000000 -13904.345700000000 2762.573240000000 41448.226600000002 1922.072390000000 10189.592800000000 13904.345700000000 0.000000000000 3720.011960000000 1922.072390000000 42347.507799999999 -7814.828610000000 -2762.573240000000 -3720.011960000000 0.000000000000 10189.592800000000 -7814.828610000000 5478.779790000000 35 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13254.756799999999 -4128.838870000000 0.000000000000 5000.000000000000 0.000000000000 -13254.756799999999 0.000000000000 -3574.170170000000 0.000000000000 0.000000000000 5000.000000000000 4128.838870000000 3574.170170000000 0.000000000000 0.000000000000 -13254.756799999999 4128.838870000000 39346.507799999999 2677.784420000000 9598.636720000000 13254.756799999999 0.000000000000 3574.170170000000 2677.784420000000 38474.156300000002 -10993.100600000000 -4128.838870000000 -3574.170170000000 0.000000000000 9598.636720000000 -10993.100600000000 7104.428220000000 35 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13175.057600000000 -225.940826000000 0.000000000000 5000.000000000000 0.000000000000 -13175.057600000000 0.000000000000 -5123.149900000000 0.000000000000 0.000000000000 5000.000000000000 225.940826000000 5123.149900000000 0.000000000000 0.000000000000 -13175.057600000000 225.940826000000 36188.007799999999 157.545090000000 13629.103499999999 13175.057600000000 0.000000000000 5123.149900000000 157.545090000000 40338.898399999998 -522.661438000000 -225.940826000000 -5123.149900000000 0.000000000000 13629.103499999999 -522.661438000000 6802.248540000000 35 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13160.812500000000 -2063.908200000000 0.000000000000 5000.000000000000 0.000000000000 -13160.812500000000 0.000000000000 -4754.993650000000 0.000000000000 0.000000000000 5000.000000000000 2063.908200000000 4754.993650000000 0.000000000000 0.000000000000 -13160.812500000000 2063.908200000000 36751.367200000001 1791.198240000000 12630.161099999999 13160.812500000000 0.000000000000 4754.993650000000 1791.198240000000 39561.289100000002 -5444.701660000000 -2063.908200000000 -4754.993650000000 0.000000000000 12630.161099999999 -5444.701660000000 6715.449710000000 36 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11719.666999999999 1775.889040000000 0.000000000000 5000.000000000000 0.000000000000 -11719.666999999999 0.000000000000 3474.191890000000 0.000000000000 0.000000000000 5000.000000000000 -1775.889040000000 -3474.191890000000 0.000000000000 0.000000000000 -11719.666999999999 -1775.889040000000 30653.333999999999 1614.593990000000 -8739.167970000000 11719.666999999999 0.000000000000 -3474.191890000000 1614.593990000000 32183.845700000002 5165.803710000000 1775.889040000000 3474.191890000000 0.000000000000 -8739.167970000000 5165.803710000000 4558.782230000000 36 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8159.324710000000 -1413.570680000000 0.000000000000 5000.000000000000 0.000000000000 -8159.324710000000 0.000000000000 2113.451660000000 0.000000000000 0.000000000000 5000.000000000000 1413.570680000000 -2113.451660000000 0.000000000000 0.000000000000 -8159.324710000000 1413.570680000000 14234.756799999999 -613.312744000000 -3487.049560000000 8159.324710000000 0.000000000000 -2113.451660000000 -613.312744000000 14881.120100000000 -2349.341800000000 -1413.570680000000 2113.451660000000 0.000000000000 -3487.049560000000 -2349.341800000000 2207.622310000000 36 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8513.129880000000 -1901.925660000000 0.000000000000 5000.000000000000 0.000000000000 -8513.129880000000 0.000000000000 1280.791140000000 0.000000000000 0.000000000000 5000.000000000000 1901.925660000000 -1280.791140000000 0.000000000000 0.000000000000 -8513.129880000000 1901.925660000000 15795.348599999999 -692.858582000000 -2193.080810000000 8513.129880000000 0.000000000000 -1280.791140000000 -692.858582000000 15915.850600000000 -3335.292240000000 -1901.925660000000 1280.791140000000 0.000000000000 -2193.080810000000 -3335.292240000000 2374.033450000000 36 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12439.019500000000 511.323059000000 0.000000000000 5000.000000000000 0.000000000000 -12439.019500000000 0.000000000000 -2147.530760000000 0.000000000000 0.000000000000 5000.000000000000 -511.323059000000 2147.530760000000 0.000000000000 0.000000000000 -12439.019500000000 -511.323059000000 33739.894500000002 709.847595000000 4864.827640000000 12439.019500000000 0.000000000000 2147.530760000000 709.847595000000 33897.625000000000 2233.847170000000 511.323059000000 -2147.530760000000 0.000000000000 4864.827640000000 2233.847170000000 3442.612790000000 36 51 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15387.702100000000 3013.533940000000 0.000000000000 5000.000000000000 0.000000000000 -15387.702100000000 0.000000000000 -2729.261720000000 0.000000000000 0.000000000000 5000.000000000000 -3013.533940000000 2729.261720000000 0.000000000000 0.000000000000 -15387.702100000000 -3013.533940000000 52099.269500000002 -1177.661010000000 8111.911620000000 15387.702100000000 0.000000000000 2729.261720000000 -1177.661010000000 50213.792999999998 10414.248000000000 3013.533940000000 -2729.261720000000 0.000000000000 8111.911620000000 10414.248000000000 5697.001950000000 36 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13210.662100000000 1813.456050000000 0.000000000000 5000.000000000000 0.000000000000 -13210.662100000000 0.000000000000 -3682.147460000000 0.000000000000 0.000000000000 5000.000000000000 -1813.456050000000 3682.147460000000 0.000000000000 0.000000000000 -13210.662100000000 -1813.456050000000 39123.578099999999 -1497.045170000000 10156.950199999999 13210.662100000000 0.000000000000 3682.147460000000 -1497.045170000000 40147.769500000002 6094.354980000000 1813.456050000000 -3682.147460000000 0.000000000000 10156.950199999999 6094.354980000000 5951.802730000000 37 39 60 4110.000000000000 0.000000000000 0.000000000000 0.000000000000 9163.364260000000 2149.353030000000 0.000000000000 4110.000000000000 0.000000000000 -9163.364260000000 0.000000000000 4319.802730000000 0.000000000000 0.000000000000 4110.000000000000 -2149.353030000000 -4319.802730000000 0.000000000000 0.000000000000 -9163.364260000000 -2149.353030000000 24350.244100000000 2886.879390000000 -10375.725600000000 9163.364260000000 0.000000000000 -4319.802730000000 2886.879390000000 26816.287100000001 5991.947270000000 2149.353030000000 4319.802730000000 0.000000000000 -10375.725600000000 5991.947270000000 7597.313480000000 37 41 60 2853.000000000000 0.000000000000 0.000000000000 0.000000000000 4080.704590000000 -912.996033000000 0.000000000000 2853.000000000000 0.000000000000 -4080.704590000000 0.000000000000 939.793213000000 0.000000000000 0.000000000000 2853.000000000000 912.996033000000 -939.793213000000 0.000000000000 0.000000000000 -4080.704590000000 912.996033000000 6397.600590000000 -325.295502000000 -1454.299930000000 4080.704590000000 0.000000000000 -939.793213000000 -325.295502000000 6575.015630000000 -1330.377810000000 -912.996033000000 939.793213000000 0.000000000000 -1454.299930000000 -1330.377810000000 1047.058720000000 37 47 60 2588.000000000000 0.000000000000 0.000000000000 0.000000000000 3746.841550000000 -826.725159000000 0.000000000000 2588.000000000000 0.000000000000 -3746.841550000000 0.000000000000 530.779236000000 0.000000000000 0.000000000000 2588.000000000000 826.725159000000 -530.779236000000 0.000000000000 0.000000000000 -3746.841550000000 826.725159000000 5944.250980000000 -168.986786000000 -870.849060000000 3746.841550000000 0.000000000000 -530.779236000000 -168.986786000000 6040.677250000000 -1206.219240000000 -826.725159000000 530.779236000000 0.000000000000 -870.849060000000 -1206.219240000000 941.699524000000 37 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8310.598630000000 18.247016900000 0.000000000000 5000.000000000000 0.000000000000 -8310.598630000000 0.000000000000 -370.630829000000 0.000000000000 0.000000000000 5000.000000000000 -18.247016900000 370.630829000000 0.000000000000 0.000000000000 -8310.598630000000 -18.247016900000 15952.442400000000 56.722007800000 535.168030000000 8310.598630000000 0.000000000000 370.630829000000 56.722007800000 15590.364299999999 914.504761000000 18.247016900000 -370.630829000000 0.000000000000 535.168030000000 914.504761000000 2113.706300000000 37 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11148.367200000001 1506.922730000000 0.000000000000 5000.000000000000 0.000000000000 -11148.367200000001 0.000000000000 -3044.155270000000 0.000000000000 0.000000000000 5000.000000000000 -1506.922730000000 3044.155270000000 0.000000000000 0.000000000000 -11148.367200000001 -1506.922730000000 27529.679700000001 -517.277039000000 6886.569820000000 11148.367200000001 0.000000000000 3044.155270000000 -517.277039000000 28266.771499999999 4023.525390000000 1506.922730000000 -3044.155270000000 0.000000000000 6886.569820000000 4023.525390000000 3931.567630000000 37 51 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13732.545899999999 3194.909910000000 0.000000000000 5000.000000000000 0.000000000000 -13732.545899999999 0.000000000000 -4963.593260000000 0.000000000000 0.000000000000 5000.000000000000 -3194.909910000000 4963.593260000000 0.000000000000 0.000000000000 -13732.545899999999 -3194.909910000000 41234.992200000001 -3156.137450000000 13736.342800000000 13732.545899999999 0.000000000000 4963.593260000000 -3156.137450000000 43360.242200000001 9070.842769999999 3194.909910000000 -4963.593260000000 0.000000000000 13736.342800000000 9070.842769999999 8408.270510000000 37 55 60 4494.000000000000 0.000000000000 0.000000000000 0.000000000000 10017.947300000000 1152.159790000000 0.000000000000 4494.000000000000 0.000000000000 -10017.947300000000 0.000000000000 -3726.332520000000 0.000000000000 0.000000000000 4494.000000000000 -1152.159790000000 3726.332520000000 0.000000000000 0.000000000000 -10017.947300000000 -1152.159790000000 25649.884800000000 -1273.554200000000 9123.667970000000 10017.947300000000 0.000000000000 3726.332520000000 -1273.554200000000 27934.785199999998 3614.863280000000 1152.159790000000 -3726.332520000000 0.000000000000 9123.667970000000 3614.863280000000 5011.762210000000 38 40 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11775.275400000000 -2172.090090000000 0.000000000000 5000.000000000000 0.000000000000 -11775.275400000000 0.000000000000 4899.397460000000 0.000000000000 0.000000000000 5000.000000000000 2172.090090000000 -4899.397460000000 0.000000000000 0.000000000000 -11775.275400000000 2172.090090000000 30051.199199999999 -2100.131350000000 -12352.709999999999 11775.275400000000 0.000000000000 -4899.397460000000 -2100.131350000000 34449.152300000002 -5006.534180000000 -2172.090090000000 4899.397460000000 0.000000000000 -12352.709999999999 -5006.534180000000 6666.351070000000 38 41 60 4474.000000000000 0.000000000000 0.000000000000 0.000000000000 8464.959960000000 -1829.172970000000 0.000000000000 4474.000000000000 0.000000000000 -8464.959960000000 0.000000000000 2669.472170000000 0.000000000000 0.000000000000 4474.000000000000 1829.172970000000 -2669.472170000000 0.000000000000 0.000000000000 -8464.959960000000 1829.172970000000 17731.083999999999 -1436.810910000000 -5980.196290000000 8464.959960000000 0.000000000000 -2669.472170000000 -1436.810910000000 19819.796900000001 -3687.673830000000 -1829.172970000000 2669.472170000000 0.000000000000 -5980.196290000000 -3687.673830000000 4087.027340000000 38 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9559.204100000001 172.290985000000 0.000000000000 5000.000000000000 0.000000000000 -9559.204100000001 0.000000000000 -682.682251000000 0.000000000000 0.000000000000 5000.000000000000 -172.290985000000 682.682251000000 0.000000000000 0.000000000000 -9559.204100000001 -172.290985000000 20394.509800000000 -1082.859620000000 2095.679690000000 9559.204100000001 0.000000000000 682.682251000000 -1082.859620000000 21242.628900000000 1138.239140000000 172.290985000000 -682.682251000000 0.000000000000 2095.679690000000 1138.239140000000 3107.023930000000 39 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10474.236300000000 -3114.322270000000 0.000000000000 5000.000000000000 0.000000000000 -10474.236300000000 0.000000000000 1606.189210000000 0.000000000000 0.000000000000 5000.000000000000 3114.322270000000 -1606.189210000000 0.000000000000 0.000000000000 -10474.236300000000 3114.322270000000 25277.851600000002 -1428.505980000000 -4096.501950000000 10474.236300000000 0.000000000000 -1606.189210000000 -1428.505980000000 25228.970700000002 -6638.572270000000 -3114.322270000000 1606.189210000000 0.000000000000 -4096.501950000000 -6638.572270000000 4372.440430000000 39 42 60 2912.000000000000 0.000000000000 0.000000000000 0.000000000000 5872.098630000000 -2109.544190000000 0.000000000000 2912.000000000000 0.000000000000 -5872.098630000000 0.000000000000 996.649963000000 0.000000000000 0.000000000000 2912.000000000000 2109.544190000000 -996.649963000000 0.000000000000 0.000000000000 -5872.098630000000 2109.544190000000 13892.966800000000 -814.070496000000 -2301.113280000000 5872.098630000000 0.000000000000 -996.649963000000 -814.070496000000 13010.863300000001 -4293.239750000000 -2109.544190000000 996.649963000000 0.000000000000 -2301.113280000000 -4293.239750000000 2338.408450000000 39 46 60 3519.000000000000 0.000000000000 0.000000000000 0.000000000000 6796.483400000000 -2609.386470000000 0.000000000000 3519.000000000000 0.000000000000 -6796.483400000000 0.000000000000 1496.057370000000 0.000000000000 0.000000000000 3519.000000000000 2609.386470000000 -1496.057370000000 0.000000000000 0.000000000000 -6796.483400000000 2609.386470000000 15657.453100000001 -1267.587770000000 -3287.329100000000 6796.483400000000 0.000000000000 -1496.057370000000 -1267.587770000000 14858.725600000000 -5122.133300000000 -2609.386470000000 1496.057370000000 0.000000000000 -3287.329100000000 -5122.133300000000 3277.540040000000 39 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9353.099609999999 -3882.043460000000 0.000000000000 5000.000000000000 0.000000000000 -9353.099609999999 0.000000000000 1103.817870000000 0.000000000000 0.000000000000 5000.000000000000 3882.043460000000 -1103.817870000000 0.000000000000 0.000000000000 -9353.099609999999 3882.043460000000 21173.054700000001 -1185.147220000000 -2183.845210000000 9353.099609999999 0.000000000000 -1103.817870000000 -1185.147220000000 19012.175800000001 -7397.351560000000 -3882.043460000000 1103.817870000000 0.000000000000 -2183.845210000000 -7397.351560000000 4371.572270000000 40 42 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9114.325199999999 -2751.352780000000 0.000000000000 5000.000000000000 0.000000000000 -9114.325199999999 0.000000000000 199.402237000000 0.000000000000 0.000000000000 5000.000000000000 2751.352780000000 -199.402237000000 0.000000000000 0.000000000000 -9114.325199999999 2751.352780000000 19602.675800000001 223.802704000000 -71.475196800000 9114.325199999999 0.000000000000 -199.402237000000 223.802704000000 18863.918000000001 -5268.879880000000 -2751.352780000000 199.402237000000 0.000000000000 -71.475196800000 -5268.879880000000 3198.272460000000 40 43 60 4952.000000000000 0.000000000000 0.000000000000 0.000000000000 8863.349609999999 -2700.156250000000 0.000000000000 4952.000000000000 0.000000000000 -8863.349609999999 0.000000000000 2298.142580000000 0.000000000000 0.000000000000 4952.000000000000 2700.156250000000 -2298.142580000000 0.000000000000 0.000000000000 -8863.349609999999 2700.156250000000 18638.800800000001 -923.190186000000 -3983.613530000000 8863.349609999999 0.000000000000 -2298.142580000000 -923.190186000000 18039.753900000000 -5080.642580000000 -2700.156250000000 2298.142580000000 0.000000000000 -3983.613530000000 -5080.642580000000 3463.299320000000 40 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10141.463900000001 -3285.473390000000 0.000000000000 5000.000000000000 0.000000000000 -10141.463900000001 0.000000000000 1473.928340000000 0.000000000000 0.000000000000 5000.000000000000 3285.473390000000 -1473.928340000000 0.000000000000 0.000000000000 -10141.463900000001 3285.473390000000 24122.623000000000 -796.767456000000 -2915.675050000000 10141.463900000001 0.000000000000 -1473.928340000000 -796.767456000000 22482.093799999999 -6731.534180000000 -3285.473390000000 1473.928340000000 0.000000000000 -2915.675050000000 -6731.534180000000 3122.279300000000 40 45 60 4855.000000000000 0.000000000000 0.000000000000 0.000000000000 10139.912100000000 -3051.033450000000 0.000000000000 4855.000000000000 0.000000000000 -10139.912100000000 0.000000000000 1924.841670000000 0.000000000000 0.000000000000 4855.000000000000 3051.033450000000 -1924.841670000000 0.000000000000 0.000000000000 -10139.912100000000 3051.033450000000 24591.002000000000 -1056.012080000000 -4015.607180000000 10139.912100000000 0.000000000000 -1924.841670000000 -1056.012080000000 23484.037100000001 -6405.694820000000 -3051.033450000000 1924.841670000000 0.000000000000 -4015.607180000000 -6405.694820000000 3172.635250000000 40 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9148.059569999999 -3249.464840000000 0.000000000000 5000.000000000000 0.000000000000 -9148.059569999999 0.000000000000 279.235107000000 0.000000000000 0.000000000000 5000.000000000000 3249.464840000000 -279.235107000000 0.000000000000 0.000000000000 -9148.059569999999 3249.464840000000 20376.037100000001 -78.713218700000 -314.635986000000 9148.059569999999 0.000000000000 -279.235107000000 -78.713218700000 18639.974600000001 -6161.854000000000 -3249.464840000000 279.235107000000 0.000000000000 -314.635986000000 -6161.854000000000 3005.180180000000 40 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8403.432620000000 -3238.527830000000 0.000000000000 5000.000000000000 0.000000000000 -8403.432620000000 0.000000000000 320.375854000000 0.000000000000 0.000000000000 5000.000000000000 3238.527830000000 -320.375854000000 0.000000000000 0.000000000000 -8403.432620000000 3238.527830000000 17337.402300000002 144.738998000000 -297.373810000000 8403.432620000000 0.000000000000 -320.375854000000 144.738998000000 15928.850600000000 -5728.993650000000 -3238.527830000000 320.375854000000 0.000000000000 -297.373810000000 -5728.993650000000 3661.976560000000 40 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8943.866210000000 -3735.297850000000 0.000000000000 5000.000000000000 0.000000000000 -8943.866210000000 0.000000000000 -1224.039180000000 0.000000000000 0.000000000000 5000.000000000000 3735.297850000000 1224.039180000000 0.000000000000 0.000000000000 -8943.866210000000 3735.297850000000 19348.941400000000 769.547546000000 1963.863770000000 8943.866210000000 0.000000000000 1224.039180000000 769.547546000000 17189.482400000001 -6802.511230000000 -3735.297850000000 -1224.039180000000 0.000000000000 1963.863770000000 -6802.511230000000 3813.468750000000 41 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11349.259800000000 -960.026794000000 0.000000000000 5000.000000000000 0.000000000000 -11349.259800000000 0.000000000000 2709.676760000000 0.000000000000 0.000000000000 5000.000000000000 960.026794000000 -2709.676760000000 0.000000000000 0.000000000000 -11349.259800000000 960.026794000000 27356.384800000000 -245.221848000000 -6134.910160000000 11349.259800000000 0.000000000000 -2709.676760000000 -245.221848000000 28283.937500000000 -2052.490230000000 -960.026794000000 2709.676760000000 0.000000000000 -6134.910160000000 -2052.490230000000 2602.380620000000 41 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11800.280300000000 -1169.777470000000 0.000000000000 5000.000000000000 0.000000000000 -11800.280300000000 0.000000000000 2144.056400000000 0.000000000000 0.000000000000 5000.000000000000 1169.777470000000 -2144.056400000000 0.000000000000 0.000000000000 -11800.280300000000 1169.777470000000 29986.191400000000 -437.449585000000 -4854.275880000000 11800.280300000000 0.000000000000 -2144.056400000000 -437.449585000000 30561.783200000002 -2439.884770000000 -1169.777470000000 2144.056400000000 0.000000000000 -4854.275880000000 -2439.884770000000 1804.509640000000 41 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12215.915000000001 -1070.900510000000 0.000000000000 5000.000000000000 0.000000000000 -12215.915000000001 0.000000000000 2446.756590000000 0.000000000000 0.000000000000 5000.000000000000 1070.900510000000 -2446.756590000000 0.000000000000 0.000000000000 -12215.915000000001 1070.900510000000 32029.072300000000 -410.977417000000 -5945.462400000000 12215.915000000001 0.000000000000 -2446.756590000000 -410.977417000000 32841.093800000002 -2193.562990000000 -1070.900510000000 2446.756590000000 0.000000000000 -5945.462400000000 -2193.562990000000 2062.839600000000 43 48 60 4513.000000000000 0.000000000000 0.000000000000 0.000000000000 11705.129900000000 -3172.831790000000 0.000000000000 4513.000000000000 0.000000000000 -11705.129900000000 0.000000000000 -4842.976560000000 0.000000000000 0.000000000000 4513.000000000000 3172.831790000000 4842.976560000000 0.000000000000 0.000000000000 -11705.129900000000 3172.831790000000 32935.355499999998 3332.112300000000 12772.972700000000 11705.129900000000 0.000000000000 4842.976560000000 3332.112300000000 36131.097699999998 -8123.688480000000 -3172.831790000000 -4842.976560000000 0.000000000000 12772.972700000000 -8123.688480000000 7729.194820000000 44 48 60 3921.000000000000 0.000000000000 0.000000000000 0.000000000000 9780.740229999999 -2936.745610000000 0.000000000000 3921.000000000000 0.000000000000 -9780.740229999999 0.000000000000 -3979.551030000000 0.000000000000 0.000000000000 3921.000000000000 2936.745610000000 3979.551030000000 0.000000000000 0.000000000000 -9780.740229999999 2936.745610000000 26868.636699999999 2964.483890000000 10050.800800000001 9780.740229999999 0.000000000000 3979.551030000000 2964.483890000000 28911.750000000000 -7274.832520000000 -2936.745610000000 -3979.551030000000 0.000000000000 10050.800800000001 -7274.832520000000 6462.935550000000 46 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11540.456099999999 -3224.823240000000 0.000000000000 5000.000000000000 0.000000000000 -11540.456099999999 0.000000000000 -5180.062990000000 0.000000000000 0.000000000000 5000.000000000000 3224.823240000000 5180.062990000000 0.000000000000 0.000000000000 -11540.456099999999 3224.823240000000 29458.250000000000 3223.117680000000 11936.706099999999 11540.456099999999 0.000000000000 5180.062990000000 3223.117680000000 32986.109400000001 -7465.538090000000 -3224.823240000000 -5180.062990000000 0.000000000000 11936.706099999999 -7465.538090000000 8019.138670000000 47 49 60 4465.000000000000 0.000000000000 0.000000000000 0.000000000000 7550.626460000000 -2145.460450000000 0.000000000000 4465.000000000000 0.000000000000 -7550.626460000000 0.000000000000 -4784.406250000000 0.000000000000 0.000000000000 4465.000000000000 2145.460450000000 4784.406250000000 0.000000000000 0.000000000000 -7550.626460000000 2145.460450000000 14334.205099999999 2254.162350000000 8118.307620000000 7550.626460000000 0.000000000000 4784.406250000000 2254.162350000000 18255.183600000000 -3679.075930000000 -2145.460450000000 -4784.406250000000 0.000000000000 8118.307620000000 -3679.075930000000 6647.100100000000 48 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10241.318400000000 -1750.032230000000 0.000000000000 5000.000000000000 0.000000000000 -10241.318400000000 0.000000000000 -4084.504390000000 0.000000000000 0.000000000000 5000.000000000000 1750.032230000000 4084.504390000000 0.000000000000 0.000000000000 -10241.318400000000 1750.032230000000 23280.331999999999 1125.273930000000 8795.210940000001 10241.318400000000 0.000000000000 4084.504390000000 1125.273930000000 25665.752000000000 -3119.079100000000 -1750.032230000000 -4084.504390000000 0.000000000000 8795.210940000001 -3119.079100000000 5256.847660000000 48 51 60 2723.000000000000 0.000000000000 0.000000000000 0.000000000000 5195.080080000000 -1183.538820000000 0.000000000000 2723.000000000000 0.000000000000 -5195.080080000000 0.000000000000 -2734.349610000000 0.000000000000 0.000000000000 2723.000000000000 1183.538820000000 2734.349610000000 0.000000000000 0.000000000000 -5195.080080000000 1183.538820000000 11045.097700000000 1300.989620000000 5444.751950000000 5195.080080000000 0.000000000000 2734.349610000000 1300.989620000000 13270.192400000000 -2387.973880000000 -1183.538820000000 -2734.349610000000 0.000000000000 5444.751950000000 -2387.973880000000 3662.679690000000 49 52 60 2986.000000000000 0.000000000000 0.000000000000 0.000000000000 5788.289550000000 -82.981010400000 0.000000000000 2986.000000000000 0.000000000000 -5788.289550000000 0.000000000000 -2194.221440000000 0.000000000000 0.000000000000 2986.000000000000 82.981010400000 2194.221440000000 0.000000000000 0.000000000000 -5788.289550000000 82.981010400000 14426.000000000000 -57.595127100000 4078.383060000000 5788.289550000000 0.000000000000 2194.221440000000 -57.595127100000 15760.885700000001 -399.157135000000 -82.981010400000 -2194.221440000000 0.000000000000 4078.383060000000 -399.157135000000 2304.010990000000 49 53 60 2566.000000000000 0.000000000000 0.000000000000 0.000000000000 3900.289550000000 -571.623169000000 0.000000000000 2566.000000000000 0.000000000000 -3900.289550000000 0.000000000000 -1429.850830000000 0.000000000000 0.000000000000 2566.000000000000 571.623169000000 1429.850830000000 0.000000000000 0.000000000000 -3900.289550000000 571.623169000000 6774.231450000000 245.573166000000 2150.381590000000 3900.289550000000 0.000000000000 1429.850830000000 245.573166000000 7352.488280000000 -1012.657530000000 -571.623169000000 -1429.850830000000 0.000000000000 2150.381590000000 -1012.657530000000 1307.353880000000 49 54 60 2338.000000000000 0.000000000000 0.000000000000 0.000000000000 3814.644780000000 168.441727000000 0.000000000000 2338.000000000000 0.000000000000 -3814.644780000000 0.000000000000 -1673.953250000000 0.000000000000 0.000000000000 2338.000000000000 -168.441727000000 1673.953250000000 0.000000000000 0.000000000000 -3814.644780000000 -168.441727000000 7658.292970000000 -363.586578000000 2991.093750000000 3814.644780000000 0.000000000000 1673.953250000000 -363.586578000000 8609.399410000000 787.378540000000 168.441727000000 -1673.953250000000 0.000000000000 2991.093750000000 787.378540000000 2075.600100000000 49 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10372.323200000001 -388.557953000000 0.000000000000 5000.000000000000 0.000000000000 -10372.323200000001 0.000000000000 -1426.014160000000 0.000000000000 0.000000000000 5000.000000000000 388.557953000000 1426.014160000000 0.000000000000 0.000000000000 -10372.323200000001 388.557953000000 24728.841799999998 -238.923752000000 3041.202640000000 10372.323200000001 0.000000000000 1426.014160000000 -238.923752000000 25404.371100000000 -107.003128000000 -388.557953000000 -1426.014160000000 0.000000000000 3041.202640000000 -107.003128000000 2891.097170000000 49 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8350.494140000001 -2605.727540000000 0.000000000000 5000.000000000000 0.000000000000 -8350.494140000001 0.000000000000 -2090.635740000000 0.000000000000 0.000000000000 5000.000000000000 2605.727540000000 2090.635740000000 0.000000000000 0.000000000000 -8350.494140000001 2605.727540000000 16159.940399999999 935.925720000000 3190.623290000000 8350.494140000001 0.000000000000 2090.635740000000 935.925720000000 15750.290999999999 -4668.272950000000 -2605.727540000000 -2090.635740000000 0.000000000000 3190.623290000000 -4668.272950000000 2996.315430000000 50 52 60 4282.000000000000 0.000000000000 0.000000000000 0.000000000000 7896.869140000000 648.807678000000 0.000000000000 4282.000000000000 0.000000000000 -7896.869140000000 0.000000000000 -1811.718510000000 0.000000000000 0.000000000000 4282.000000000000 -648.807678000000 1811.718510000000 0.000000000000 0.000000000000 -7896.869140000000 -648.807678000000 16777.111300000000 -534.229614000000 2756.260740000000 7896.869140000000 0.000000000000 1811.718510000000 -534.229614000000 17549.693400000000 737.685364000000 648.807678000000 -1811.718510000000 0.000000000000 2756.260740000000 737.685364000000 1989.548580000000 50 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9493.478520000001 -864.856689000000 0.000000000000 5000.000000000000 0.000000000000 -9493.478520000001 0.000000000000 -1358.899660000000 0.000000000000 0.000000000000 5000.000000000000 864.856689000000 1358.899660000000 0.000000000000 0.000000000000 -9493.478520000001 864.856689000000 19773.908200000002 11.017682100000 2385.264650000000 9493.478520000001 0.000000000000 1358.899660000000 11.017682100000 19659.505900000000 -1927.927490000000 -864.856689000000 -1358.899660000000 0.000000000000 2385.264650000000 -1927.927490000000 1640.525390000000 50 54 60 3202.000000000000 0.000000000000 0.000000000000 0.000000000000 5624.126950000000 570.504456000000 0.000000000000 3202.000000000000 0.000000000000 -5624.126950000000 0.000000000000 -1047.464970000000 0.000000000000 0.000000000000 3202.000000000000 -570.504456000000 1047.464970000000 0.000000000000 0.000000000000 -5624.126950000000 -570.504456000000 11124.660200000000 -320.762787000000 1818.627320000000 5624.126950000000 0.000000000000 1047.464970000000 -320.762787000000 11267.340800000000 1245.989380000000 570.504456000000 -1047.464970000000 0.000000000000 1818.627320000000 1245.989380000000 1437.278080000000 50 55 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10658.523400000000 -782.397156000000 0.000000000000 5000.000000000000 0.000000000000 -10658.523400000000 0.000000000000 301.227112000000 0.000000000000 0.000000000000 5000.000000000000 782.397156000000 -301.227112000000 0.000000000000 0.000000000000 -10658.523400000000 782.397156000000 25112.029299999998 14.437816600000 -1044.804320000000 10658.523400000000 0.000000000000 -301.227112000000 14.437816600000 25158.453099999999 -1363.461670000000 -782.397156000000 301.227112000000 0.000000000000 -1044.804320000000 -1363.461670000000 2375.556150000000 50 56 60 4568.000000000000 0.000000000000 0.000000000000 0.000000000000 7929.309570000000 -1425.855220000000 0.000000000000 4568.000000000000 0.000000000000 -7929.309570000000 0.000000000000 -867.554260000000 0.000000000000 0.000000000000 4568.000000000000 1425.855220000000 867.554260000000 0.000000000000 0.000000000000 -7929.309570000000 1425.855220000000 15168.211900000000 97.622146600000 1208.377320000000 7929.309570000000 0.000000000000 867.554260000000 97.622146600000 15119.963900000001 -2742.246580000000 -1425.855220000000 -867.554260000000 0.000000000000 1208.377320000000 -2742.246580000000 1571.674930000000 50 57 60 3020.000000000000 0.000000000000 0.000000000000 0.000000000000 4055.755370000000 418.371796000000 0.000000000000 3020.000000000000 0.000000000000 -4055.755370000000 0.000000000000 -1403.663940000000 0.000000000000 0.000000000000 3020.000000000000 -418.371796000000 1403.663940000000 0.000000000000 0.000000000000 -4055.755370000000 -418.371796000000 6100.752440000000 -200.595428000000 1889.875730000000 4055.755370000000 0.000000000000 1403.663940000000 -200.595428000000 6533.074710000000 526.313354000000 418.371796000000 -1403.663940000000 0.000000000000 1889.875730000000 526.313354000000 1155.245000000000 50 58 60 4200.000000000000 0.000000000000 0.000000000000 0.000000000000 5921.604000000000 506.154816000000 0.000000000000 4200.000000000000 0.000000000000 -5921.604000000000 0.000000000000 -2004.284670000000 0.000000000000 0.000000000000 4200.000000000000 -506.154816000000 2004.284670000000 0.000000000000 0.000000000000 -5921.604000000000 -506.154816000000 9451.365229999999 -375.957703000000 2794.830810000000 5921.604000000000 0.000000000000 2004.284670000000 -375.957703000000 9955.314450000000 517.639038000000 506.154816000000 -2004.284670000000 0.000000000000 2794.830810000000 517.639038000000 1918.101320000000 51 52 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9409.589840000001 -929.446228000000 0.000000000000 5000.000000000000 0.000000000000 -9409.589840000001 0.000000000000 -830.427429000000 0.000000000000 0.000000000000 5000.000000000000 929.446228000000 830.427429000000 0.000000000000 0.000000000000 -9409.589840000001 929.446228000000 21343.119100000000 155.558868000000 285.099457000000 9409.589840000001 0.000000000000 830.427429000000 155.558868000000 21542.980500000001 -1602.412480000000 -929.446228000000 -830.427429000000 0.000000000000 285.099457000000 -1602.412480000000 2208.551760000000 51 53 60 3323.000000000000 0.000000000000 0.000000000000 0.000000000000 5658.101070000000 -1157.552490000000 0.000000000000 3323.000000000000 0.000000000000 -5658.101070000000 0.000000000000 -209.178909000000 0.000000000000 0.000000000000 3323.000000000000 1157.552490000000 209.178909000000 0.000000000000 0.000000000000 -5658.101070000000 1157.552490000000 11100.627899999999 -208.915054000000 90.019424400000 5658.101070000000 0.000000000000 209.178909000000 -208.915054000000 10703.106400000001 -2224.442380000000 -1157.552490000000 -209.178909000000 0.000000000000 90.019424400000 -2224.442380000000 1217.301640000000 51 54 60 3152.000000000000 0.000000000000 0.000000000000 0.000000000000 5682.907230000000 -357.440918000000 0.000000000000 3152.000000000000 0.000000000000 -5682.907230000000 0.000000000000 -190.360779000000 0.000000000000 0.000000000000 3152.000000000000 357.440918000000 190.360779000000 0.000000000000 0.000000000000 -5682.907230000000 357.440918000000 12262.081099999999 -148.582779000000 -47.694278700000 5682.907230000000 0.000000000000 190.360779000000 -148.582779000000 12191.823200000001 -310.350128000000 -357.440918000000 -190.360779000000 0.000000000000 -47.694278700000 -310.350128000000 1179.385990000000 51 57 60 2314.000000000000 0.000000000000 0.000000000000 0.000000000000 3204.041020000000 -422.621307000000 0.000000000000 2314.000000000000 0.000000000000 -3204.041020000000 0.000000000000 -695.122314000000 0.000000000000 0.000000000000 2314.000000000000 422.621307000000 695.122314000000 0.000000000000 0.000000000000 -3204.041020000000 422.621307000000 4781.637700000000 138.782181000000 967.594849000000 3204.041020000000 0.000000000000 695.122314000000 138.782181000000 4864.532710000000 -599.637085000000 -422.621307000000 -695.122314000000 0.000000000000 967.594849000000 -599.637085000000 625.954895000000 51 58 60 3313.000000000000 0.000000000000 0.000000000000 0.000000000000 4564.241210000000 -225.384430000000 0.000000000000 3313.000000000000 0.000000000000 -4564.241210000000 0.000000000000 -1225.104610000000 0.000000000000 0.000000000000 3313.000000000000 225.384430000000 1225.104610000000 0.000000000000 0.000000000000 -4564.241210000000 225.384430000000 6727.151370000000 -67.590080300000 1652.086550000000 4564.241210000000 0.000000000000 1225.104610000000 -67.590080300000 7081.023930000000 -384.845764000000 -225.384430000000 -1225.104610000000 0.000000000000 1652.086550000000 -384.845764000000 1065.714720000000 52 57 60 2918.000000000000 0.000000000000 0.000000000000 0.000000000000 2854.030760000000 -194.274780000000 0.000000000000 2918.000000000000 0.000000000000 -2854.030760000000 0.000000000000 -794.390198000000 0.000000000000 0.000000000000 2918.000000000000 194.274780000000 794.390198000000 0.000000000000 0.000000000000 -2854.030760000000 194.274780000000 3046.832030000000 93.035400400000 870.459229000000 2854.030760000000 0.000000000000 794.390198000000 93.035400400000 3281.391850000000 -221.247849000000 -194.274780000000 -794.390198000000 0.000000000000 870.459229000000 -221.247849000000 621.355713000000 52 58 60 2785.000000000000 0.000000000000 0.000000000000 0.000000000000 2698.507570000000 54.941680900000 0.000000000000 2785.000000000000 0.000000000000 -2698.507570000000 0.000000000000 -772.753906000000 0.000000000000 0.000000000000 2785.000000000000 -54.941680900000 772.753906000000 0.000000000000 0.000000000000 -2698.507570000000 -54.941680900000 2809.254880000000 -63.838901500000 820.981018000000 2698.507570000000 0.000000000000 772.753906000000 -63.838901500000 3067.811040000000 49.548122400000 54.941680900000 -772.753906000000 0.000000000000 820.981018000000 49.548122400000 531.243225000000 53 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6306.167970000000 56.399871800000 0.000000000000 5000.000000000000 0.000000000000 -6306.167970000000 0.000000000000 -2359.907960000000 0.000000000000 0.000000000000 5000.000000000000 -56.399871800000 2359.907960000000 0.000000000000 0.000000000000 -6306.167970000000 -56.399871800000 8558.137699999999 41.720504800000 3173.663330000000 6306.167970000000 0.000000000000 2359.907960000000 41.720504800000 9607.735350000001 14.747496600000 56.399871800000 -2359.907960000000 0.000000000000 3173.663330000000 14.747496600000 1901.081790000000 54 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8475.375000000000 -1893.358400000000 0.000000000000 5000.000000000000 0.000000000000 -8475.375000000000 0.000000000000 -2428.455570000000 0.000000000000 0.000000000000 5000.000000000000 1893.358400000000 2428.455570000000 0.000000000000 0.000000000000 -8475.375000000000 1893.358400000000 15524.380900000000 908.963257000000 4348.837400000000 8475.375000000000 0.000000000000 2428.455570000000 908.963257000000 16392.382799999999 -3283.768070000000 -1893.358400000000 -2428.455570000000 0.000000000000 4348.837400000000 -3283.768070000000 2645.630370000000 54 57 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8441.608399999999 589.899658000000 0.000000000000 5000.000000000000 0.000000000000 -8441.608399999999 0.000000000000 -2865.481200000000 0.000000000000 0.000000000000 5000.000000000000 -589.899658000000 2865.481200000000 0.000000000000 0.000000000000 -8441.608399999999 -589.899658000000 15345.614299999999 -350.853363000000 4997.978520000000 8441.608399999999 0.000000000000 2865.481200000000 -350.853363000000 16328.280300000000 1064.527220000000 589.899658000000 -2865.481200000000 0.000000000000 4997.978520000000 1064.527220000000 2781.261470000000 54 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8494.522460000000 50.227985400000 0.000000000000 5000.000000000000 0.000000000000 -8494.522460000000 0.000000000000 -3047.172610000000 0.000000000000 0.000000000000 5000.000000000000 -50.227985400000 3047.172610000000 0.000000000000 0.000000000000 -8494.522460000000 -50.227985400000 15455.743200000001 -58.030658700000 5345.536130000000 8494.522460000000 0.000000000000 3047.172610000000 -58.030658700000 16756.119100000000 98.156913800000 50.227985400000 -3047.172610000000 0.000000000000 5345.536130000000 98.156913800000 2950.097410000000 55 56 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7664.336910000000 -3142.197270000000 0.000000000000 5000.000000000000 0.000000000000 -7664.336910000000 0.000000000000 -4752.804690000000 0.000000000000 0.000000000000 5000.000000000000 3142.197270000000 4752.804690000000 0.000000000000 0.000000000000 -7664.336910000000 3142.197270000000 14339.001000000000 3039.414550000000 7342.161620000000 7664.336910000000 0.000000000000 4752.804690000000 3039.414550000000 16922.638700000000 -4883.294430000000 -3142.197270000000 -4752.804690000000 0.000000000000 7342.161620000000 -4883.294430000000 7385.864260000000 55 58 60 4535.000000000000 0.000000000000 0.000000000000 0.000000000000 6405.646000000000 -1753.611820000000 0.000000000000 4535.000000000000 0.000000000000 -6405.646000000000 0.000000000000 -5010.427250000000 0.000000000000 0.000000000000 4535.000000000000 1753.611820000000 5010.427250000000 0.000000000000 0.000000000000 -6405.646000000000 1753.611820000000 10673.925800000001 2001.980710000000 7144.958010000000 6405.646000000000 0.000000000000 5010.427250000000 2001.980710000000 14932.611300000000 -2504.756350000000 -1753.611820000000 -5010.427250000000 0.000000000000 7144.958010000000 -2504.756350000000 7299.490230000000 57 59 60 3881.000000000000 0.000000000000 0.000000000000 0.000000000000 8828.833979999999 -2437.088130000000 0.000000000000 3881.000000000000 0.000000000000 -8828.833979999999 0.000000000000 -2298.881590000000 0.000000000000 0.000000000000 3881.000000000000 2437.088130000000 2298.881590000000 0.000000000000 0.000000000000 -8828.833979999999 2437.088130000000 22413.312500000000 1649.964840000000 5723.712890000000 8828.833979999999 0.000000000000 2298.881590000000 1649.964840000000 22828.195299999999 -5774.345210000000 -2437.088130000000 -2298.881590000000 0.000000000000 5723.712890000000 -5774.345210000000 3876.729490000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-home_md-home_md_scan9_2012_sep_30/gt.info ================================================ 0 1 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11744.719700000000 -2797.413820000000 0.000000000000 5000.000000000000 0.000000000000 -11744.719700000000 0.000000000000 4943.176760000000 0.000000000000 0.000000000000 5000.000000000000 2797.413820000000 -4943.176760000000 0.000000000000 0.000000000000 -11744.719700000000 2797.413820000000 30446.507799999999 -2776.037600000000 -11673.271500000001 11744.719700000000 0.000000000000 -4943.176760000000 -2776.037600000000 33166.312500000000 -6371.289550000000 -2797.413820000000 4943.176760000000 0.000000000000 -11673.271500000001 -6371.289550000000 7775.080080000000 0 51 60 2979.000000000000 0.000000000000 0.000000000000 0.000000000000 6396.876950000000 -533.427246000000 0.000000000000 2979.000000000000 0.000000000000 -6396.876950000000 0.000000000000 -1444.490600000000 0.000000000000 0.000000000000 2979.000000000000 533.427246000000 1444.490600000000 0.000000000000 0.000000000000 -6396.876950000000 533.427246000000 14250.647499999999 -57.106777200000 3136.998290000000 6396.876950000000 0.000000000000 1444.490600000000 -57.106777200000 14858.997100000001 -1090.261840000000 -533.427246000000 -1444.490600000000 0.000000000000 3136.998290000000 -1090.261840000000 1560.083860000000 0 52 60 2661.000000000000 0.000000000000 0.000000000000 0.000000000000 5816.492680000000 -584.606140000000 0.000000000000 2661.000000000000 0.000000000000 -5816.492680000000 0.000000000000 -787.296387000000 0.000000000000 0.000000000000 2661.000000000000 584.606140000000 787.296387000000 0.000000000000 0.000000000000 -5816.492680000000 584.606140000000 13082.170899999999 80.063026400000 1734.379270000000 5816.492680000000 0.000000000000 787.296387000000 80.063026400000 13171.298800000000 -1218.210330000000 -584.606140000000 -787.296387000000 0.000000000000 1734.379270000000 -1218.210330000000 727.018494000000 0 53 60 3315.000000000000 0.000000000000 0.000000000000 0.000000000000 7130.675780000000 -873.828247000000 0.000000000000 3315.000000000000 0.000000000000 -7130.675780000000 0.000000000000 -890.250854000000 0.000000000000 0.000000000000 3315.000000000000 873.828247000000 890.250854000000 0.000000000000 0.000000000000 -7130.675780000000 873.828247000000 15745.631799999999 185.145950000000 1888.727660000000 7130.675780000000 0.000000000000 890.250854000000 185.145950000000 15844.120100000000 -1852.566040000000 -873.828247000000 -890.250854000000 0.000000000000 1888.727660000000 -1852.566040000000 826.064941000000 0 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10943.389600000000 -712.672913000000 0.000000000000 5000.000000000000 0.000000000000 -10943.389600000000 0.000000000000 -1822.421630000000 0.000000000000 0.000000000000 5000.000000000000 712.672913000000 1822.421630000000 0.000000000000 0.000000000000 -10943.389600000000 712.672913000000 24427.335899999998 50.606960300000 3944.555180000000 10943.389600000000 0.000000000000 1822.421630000000 50.606960300000 25262.443400000000 -1483.576540000000 -712.672913000000 -1822.421630000000 0.000000000000 3944.555180000000 -1483.576540000000 1582.764400000000 0 55 60 3722.000000000000 0.000000000000 0.000000000000 0.000000000000 8327.467769999999 814.830566000000 0.000000000000 3722.000000000000 0.000000000000 -8327.467769999999 0.000000000000 -1751.748170000000 0.000000000000 0.000000000000 3722.000000000000 -814.830566000000 1751.748170000000 0.000000000000 0.000000000000 -8327.467769999999 -814.830566000000 19213.132799999999 -306.051697000000 3825.979000000000 8327.467769999999 0.000000000000 1751.748170000000 -306.051697000000 19988.070299999999 1866.129640000000 814.830566000000 -1751.748170000000 0.000000000000 3825.979000000000 1866.129640000000 1779.816770000000 0 56 60 2640.000000000000 0.000000000000 0.000000000000 0.000000000000 6067.018070000000 1160.746950000000 0.000000000000 2640.000000000000 0.000000000000 -6067.018070000000 0.000000000000 -1122.629030000000 0.000000000000 0.000000000000 2640.000000000000 -1160.746950000000 1122.629030000000 0.000000000000 0.000000000000 -6067.018070000000 -1160.746950000000 14753.332000000000 -288.174408000000 2501.759520000000 6067.018070000000 0.000000000000 1122.629030000000 -288.174408000000 14853.627899999999 2701.519780000000 1160.746950000000 -1122.629030000000 0.000000000000 2501.759520000000 2701.519780000000 1612.396850000000 0 57 60 3345.000000000000 0.000000000000 0.000000000000 0.000000000000 7633.316890000000 1229.259520000000 0.000000000000 3345.000000000000 0.000000000000 -7633.316890000000 0.000000000000 -1373.934200000000 0.000000000000 0.000000000000 3345.000000000000 -1229.259520000000 1373.934200000000 0.000000000000 0.000000000000 -7633.316890000000 -1229.259520000000 18310.851600000002 -319.803192000000 3045.980960000000 7633.316890000000 0.000000000000 1373.934200000000 -319.803192000000 18454.744100000000 2871.564700000000 1229.259520000000 -1373.934200000000 0.000000000000 3045.980960000000 2871.564700000000 1777.966310000000 0 58 60 4717.000000000000 0.000000000000 0.000000000000 0.000000000000 10655.951200000000 808.757141000000 0.000000000000 4717.000000000000 0.000000000000 -10655.951200000000 0.000000000000 -1570.993900000000 0.000000000000 0.000000000000 4717.000000000000 -808.757141000000 1570.993900000000 0.000000000000 0.000000000000 -10655.951200000000 -808.757141000000 25069.529299999998 -119.004929000000 3462.091800000000 10655.951200000000 0.000000000000 1570.993900000000 -119.004929000000 25162.750000000000 1945.008060000000 808.757141000000 -1570.993900000000 0.000000000000 3462.091800000000 1945.008060000000 1895.612060000000 0 59 60 3234.000000000000 0.000000000000 0.000000000000 0.000000000000 7079.021970000000 -141.059082000000 0.000000000000 3234.000000000000 0.000000000000 -7079.021970000000 0.000000000000 -1639.176150000000 0.000000000000 0.000000000000 3234.000000000000 141.059082000000 1639.176150000000 0.000000000000 0.000000000000 -7079.021970000000 141.059082000000 15887.093800000001 -64.390998800000 3639.552730000000 7079.021970000000 0.000000000000 1639.176150000000 -64.390998800000 16648.285199999998 -219.232864000000 -141.059082000000 -1639.176150000000 0.000000000000 3639.552730000000 -219.232864000000 1319.384890000000 1 3 60 4899.000000000000 0.000000000000 0.000000000000 0.000000000000 11920.683600000000 68.881134000000 0.000000000000 4899.000000000000 0.000000000000 -11920.683600000000 0.000000000000 5179.572750000000 0.000000000000 0.000000000000 4899.000000000000 -68.881134000000 -5179.572750000000 0.000000000000 0.000000000000 -11920.683600000000 -68.881134000000 30775.496100000000 468.578369000000 -13177.147499999999 11920.683600000000 0.000000000000 -5179.572750000000 468.578369000000 36129.183599999997 714.890869000000 68.881134000000 5179.572750000000 0.000000000000 -13177.147499999999 714.890869000000 6765.265630000000 1 4 60 4587.000000000000 0.000000000000 0.000000000000 0.000000000000 9944.355470000000 -883.273254000000 0.000000000000 4587.000000000000 0.000000000000 -9944.355470000000 0.000000000000 3927.578370000000 0.000000000000 0.000000000000 4587.000000000000 883.273254000000 -3927.578370000000 0.000000000000 0.000000000000 -9944.355470000000 883.273254000000 23049.581999999999 25.667610200000 -9241.850590000000 9944.355470000000 0.000000000000 -3927.578370000000 25.667610200000 26890.218799999999 -1437.807010000000 -883.273254000000 3927.578370000000 0.000000000000 -9241.850590000000 -1437.807010000000 5485.171880000000 1 5 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12761.249000000000 613.461609000000 0.000000000000 5000.000000000000 0.000000000000 -12761.249000000000 0.000000000000 5147.336910000000 0.000000000000 0.000000000000 5000.000000000000 -613.461609000000 -5147.336910000000 0.000000000000 0.000000000000 -12761.249000000000 -613.461609000000 34690.300799999997 1067.498170000000 -13694.456099999999 12761.249000000000 0.000000000000 -5147.336910000000 1067.498170000000 39577.195299999999 2143.575440000000 613.461609000000 5147.336910000000 0.000000000000 -13694.456099999999 2143.575440000000 6782.777830000000 1 6 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13868.088900000001 2114.518070000000 0.000000000000 5000.000000000000 0.000000000000 -13868.088900000001 0.000000000000 5662.895510000000 0.000000000000 0.000000000000 5000.000000000000 -2114.518070000000 -5662.895510000000 0.000000000000 0.000000000000 -13868.088900000001 -2114.518070000000 40625.894500000002 2357.320800000000 -15619.618200000001 13868.088900000001 0.000000000000 -5662.895510000000 2357.320800000000 45242.796900000001 6059.635250000000 2114.518070000000 5662.895510000000 0.000000000000 -15619.618200000001 6059.635250000000 8329.153319999999 1 7 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14407.621100000000 668.434387000000 0.000000000000 5000.000000000000 0.000000000000 -14407.621100000000 0.000000000000 4620.889650000000 0.000000000000 0.000000000000 5000.000000000000 -668.434387000000 -4620.889650000000 0.000000000000 0.000000000000 -14407.621100000000 -668.434387000000 44100.140599999999 858.039307000000 -13440.186500000000 14407.621100000000 0.000000000000 -4620.889650000000 858.039307000000 47427.417999999998 2271.799070000000 668.434387000000 4620.889650000000 0.000000000000 -13440.186500000000 2271.799070000000 5764.942380000000 1 8 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15316.314500000000 -204.924149000000 0.000000000000 5000.000000000000 0.000000000000 -15316.314500000000 0.000000000000 4341.189450000000 0.000000000000 0.000000000000 5000.000000000000 204.924149000000 -4341.189450000000 0.000000000000 0.000000000000 -15316.314500000000 204.924149000000 48415.242200000001 89.860496500000 -12942.150400000000 15316.314500000000 0.000000000000 -4341.189450000000 89.860496500000 51823.367200000001 -695.721375000000 -204.924149000000 4341.189450000000 0.000000000000 -12942.150400000000 -695.721375000000 5065.453610000000 1 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16312.120100000000 -446.291656000000 0.000000000000 5000.000000000000 0.000000000000 -16312.120100000000 0.000000000000 4245.980470000000 0.000000000000 0.000000000000 5000.000000000000 446.291656000000 -4245.980470000000 0.000000000000 0.000000000000 -16312.120100000000 446.291656000000 53900.339800000002 -392.593689000000 -13732.123000000000 16312.120100000000 0.000000000000 -4245.980470000000 -392.593689000000 57124.167999999998 -1460.239620000000 -446.291656000000 4245.980470000000 0.000000000000 -13732.123000000000 -1460.239620000000 4203.527830000000 1 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13086.622100000001 -357.322968000000 0.000000000000 5000.000000000000 0.000000000000 -13086.622100000001 0.000000000000 4443.027340000000 0.000000000000 0.000000000000 5000.000000000000 357.322968000000 -4443.027340000000 0.000000000000 0.000000000000 -13086.622100000001 357.322968000000 36837.882799999999 -10.970220600000 -12154.532200000000 13086.622100000001 0.000000000000 -4443.027340000000 -10.970220600000 40609.136700000003 -311.011536000000 -357.322968000000 4443.027340000000 0.000000000000 -12154.532200000000 -311.011536000000 5018.866210000000 1 46 60 3126.000000000000 0.000000000000 0.000000000000 0.000000000000 6741.898440000000 -474.549683000000 0.000000000000 3126.000000000000 0.000000000000 -6741.898440000000 0.000000000000 2673.573490000000 0.000000000000 0.000000000000 3126.000000000000 474.549683000000 -2673.573490000000 0.000000000000 0.000000000000 -6741.898440000000 474.549683000000 15765.753900000000 -86.380683900000 -6240.578130000000 6741.898440000000 0.000000000000 -2673.573490000000 -86.380683900000 18020.691400000000 -625.940002000000 -474.549683000000 2673.573490000000 0.000000000000 -6240.578130000000 -625.940002000000 3360.165280000000 2 3 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10198.294900000001 315.046570000000 0.000000000000 5000.000000000000 0.000000000000 -10198.294900000001 0.000000000000 2120.171630000000 0.000000000000 0.000000000000 5000.000000000000 -315.046570000000 -2120.171630000000 0.000000000000 0.000000000000 -10198.294900000001 -315.046570000000 23783.146499999999 602.293457000000 -4844.102050000000 10198.294900000001 0.000000000000 -2120.171630000000 602.293457000000 24421.712899999999 1813.650760000000 315.046570000000 2120.171630000000 0.000000000000 -4844.102050000000 1813.650760000000 3339.638920000000 2 4 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10211.079100000001 -172.695694000000 0.000000000000 5000.000000000000 0.000000000000 -10211.079100000001 0.000000000000 2319.036130000000 0.000000000000 0.000000000000 5000.000000000000 172.695694000000 -2319.036130000000 0.000000000000 0.000000000000 -10211.079100000001 172.695694000000 23308.972699999998 248.538559000000 -5119.230470000000 10211.079100000001 0.000000000000 -2319.036130000000 248.538559000000 24311.291000000001 622.765259000000 -172.695694000000 2319.036130000000 0.000000000000 -5119.230470000000 622.765259000000 2913.546140000000 2 6 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12671.984399999999 1440.205930000000 0.000000000000 5000.000000000000 0.000000000000 -12671.984399999999 0.000000000000 2895.898680000000 0.000000000000 0.000000000000 5000.000000000000 -1440.205930000000 -2895.898680000000 0.000000000000 0.000000000000 -12671.984399999999 -1440.205930000000 34000.773399999998 690.188293000000 -6920.194340000000 12671.984399999999 0.000000000000 -2895.898680000000 690.188293000000 35337.062500000000 3933.861570000000 1440.205930000000 2895.898680000000 0.000000000000 -6920.194340000000 3933.861570000000 3974.378660000000 2 9 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16012.636699999999 1563.460450000000 0.000000000000 5000.000000000000 0.000000000000 -16012.636699999999 0.000000000000 -5777.947750000000 0.000000000000 0.000000000000 5000.000000000000 -1563.460450000000 5777.947750000000 0.000000000000 0.000000000000 -16012.636699999999 -1563.460450000000 52559.324200000003 -1654.102050000000 18586.123000000000 16012.636699999999 0.000000000000 5777.947750000000 -1654.102050000000 58225.273399999998 4841.254390000000 1563.460450000000 -5777.947750000000 0.000000000000 18586.123000000000 4841.254390000000 8081.688960000000 2 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16002.892599999999 1388.987060000000 0.000000000000 5000.000000000000 0.000000000000 -16002.892599999999 0.000000000000 -5827.894530000000 0.000000000000 0.000000000000 5000.000000000000 -1388.987060000000 5827.894530000000 0.000000000000 0.000000000000 -16002.892599999999 -1388.987060000000 52666.429700000001 -1524.391600000000 18700.441400000000 16002.892599999999 0.000000000000 5827.894530000000 -1524.391600000000 58231.843800000002 4279.427250000000 1388.987060000000 -5827.894530000000 0.000000000000 18700.441400000000 4279.427250000000 8334.131840000000 2 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15914.346700000000 553.207153000000 0.000000000000 5000.000000000000 0.000000000000 -15914.346700000000 0.000000000000 -5302.120610000000 0.000000000000 0.000000000000 5000.000000000000 -553.207153000000 5302.120610000000 0.000000000000 0.000000000000 -15914.346700000000 -553.207153000000 51592.078099999999 -659.389221000000 17066.025399999999 15914.346700000000 0.000000000000 5302.120610000000 -659.389221000000 56898.882799999999 1725.753910000000 553.207153000000 -5302.120610000000 0.000000000000 17066.025399999999 1725.753910000000 6942.698730000000 2 38 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10749.884800000000 -1176.771240000000 0.000000000000 5000.000000000000 0.000000000000 -10749.884800000000 0.000000000000 1866.599000000000 0.000000000000 0.000000000000 5000.000000000000 1176.771240000000 -1866.599000000000 0.000000000000 0.000000000000 -10749.884800000000 1176.771240000000 25171.085899999998 -58.279136700000 -3549.495850000000 10749.884800000000 0.000000000000 -1866.599000000000 -58.279136700000 26278.681600000000 -2201.231200000000 -1176.771240000000 1866.599000000000 0.000000000000 -3549.495850000000 -2201.231200000000 3031.559080000000 2 39 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9848.627930000001 -393.582672000000 0.000000000000 5000.000000000000 0.000000000000 -9848.627930000001 0.000000000000 2948.643070000000 0.000000000000 0.000000000000 5000.000000000000 393.582672000000 -2948.643070000000 0.000000000000 0.000000000000 -9848.627930000001 393.582672000000 21761.224600000001 413.268890000000 -6264.859380000000 9848.627930000001 0.000000000000 -2948.643070000000 413.268890000000 23322.529299999998 21.892108900000 -393.582672000000 2948.643070000000 0.000000000000 -6264.859380000000 21.892108900000 4019.023930000000 2 40 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10018.620100000000 -853.239319000000 0.000000000000 5000.000000000000 0.000000000000 -10018.620100000000 0.000000000000 3090.223880000000 0.000000000000 0.000000000000 5000.000000000000 853.239319000000 -3090.223880000000 0.000000000000 0.000000000000 -10018.620100000000 853.239319000000 21920.386699999999 -121.122437000000 -6567.328610000000 10018.620100000000 0.000000000000 -3090.223880000000 -121.122437000000 23985.484400000001 -1090.916020000000 -853.239319000000 3090.223880000000 0.000000000000 -6567.328610000000 -1090.916020000000 3697.900390000000 2 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9037.390630000000 -1517.743770000000 0.000000000000 5000.000000000000 0.000000000000 -9037.390630000000 0.000000000000 2650.611570000000 0.000000000000 0.000000000000 5000.000000000000 1517.743770000000 -2650.611570000000 0.000000000000 0.000000000000 -9037.390630000000 1517.743770000000 17647.293000000001 -627.636536000000 -5070.589360000000 9037.390630000000 0.000000000000 -2650.611570000000 -627.636536000000 19319.919900000001 -2570.289060000000 -1517.743770000000 2650.611570000000 0.000000000000 -5070.589360000000 -2570.289060000000 3087.204350000000 2 45 60 4559.000000000000 0.000000000000 0.000000000000 0.000000000000 8177.102050000000 -946.810608000000 0.000000000000 4559.000000000000 0.000000000000 -8177.102050000000 0.000000000000 3135.535400000000 0.000000000000 0.000000000000 4559.000000000000 946.810608000000 -3135.535400000000 0.000000000000 0.000000000000 -8177.102050000000 946.810608000000 15819.236300000000 -330.932739000000 -6147.561520000000 8177.102050000000 0.000000000000 -3135.535400000000 -330.932739000000 18258.277300000002 -1387.985600000000 -946.810608000000 3135.535400000000 0.000000000000 -6147.561520000000 -1387.985600000000 3424.535890000000 2 46 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10100.031300000001 -324.511688000000 0.000000000000 5000.000000000000 0.000000000000 -10100.031300000001 0.000000000000 3209.427000000000 0.000000000000 0.000000000000 5000.000000000000 324.511688000000 -3209.427000000000 0.000000000000 0.000000000000 -10100.031300000001 324.511688000000 22813.056600000000 371.590179000000 -6847.582030000000 10100.031300000001 0.000000000000 -3209.427000000000 371.590179000000 24516.960899999998 161.945221000000 -324.511688000000 3209.427000000000 0.000000000000 -6847.582030000000 161.945221000000 4224.492680000000 2 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8983.279300000000 -1551.041500000000 0.000000000000 5000.000000000000 0.000000000000 -8983.279300000000 0.000000000000 2798.492430000000 0.000000000000 0.000000000000 5000.000000000000 1551.041500000000 -2798.492430000000 0.000000000000 0.000000000000 -8983.279300000000 1551.041500000000 17600.083999999999 -712.694519000000 -5226.340330000000 8983.279300000000 0.000000000000 -2798.492430000000 -712.694519000000 19266.892599999999 -2578.625730000000 -1551.041500000000 2798.492430000000 0.000000000000 -5226.340330000000 -2578.625730000000 3111.890630000000 2 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7960.531250000000 -1861.317140000000 0.000000000000 5000.000000000000 0.000000000000 -7960.531250000000 0.000000000000 1631.488650000000 0.000000000000 0.000000000000 5000.000000000000 1861.317140000000 -1631.488650000000 0.000000000000 0.000000000000 -7960.531250000000 1861.317140000000 13959.001000000000 -653.013977000000 -2609.430420000000 7960.531250000000 0.000000000000 -1631.488650000000 -653.013977000000 14430.212900000000 -2960.309330000000 -1861.317140000000 1631.488650000000 0.000000000000 -2609.430420000000 -2960.309330000000 2011.998660000000 3 8 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12579.910200000000 434.197998000000 0.000000000000 5000.000000000000 0.000000000000 -12579.910200000000 0.000000000000 -4993.930180000000 0.000000000000 0.000000000000 5000.000000000000 -434.197998000000 4993.930180000000 0.000000000000 0.000000000000 -12579.910200000000 -434.197998000000 32507.037100000001 -321.013580000000 12670.125000000000 12579.910200000000 0.000000000000 4993.930180000000 -321.013580000000 37034.093800000002 1099.119260000000 434.197998000000 -4993.930180000000 0.000000000000 12670.125000000000 1099.119260000000 5969.548340000000 3 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9783.257809999999 -298.751190000000 0.000000000000 5000.000000000000 0.000000000000 -9783.257809999999 0.000000000000 2207.787110000000 0.000000000000 0.000000000000 5000.000000000000 298.751190000000 -2207.787110000000 0.000000000000 0.000000000000 -9783.257809999999 298.751190000000 20869.328099999999 132.285721000000 -4513.105960000000 9783.257809999999 0.000000000000 -2207.787110000000 132.285721000000 21806.642599999999 -24.616924300000 -298.751190000000 2207.787110000000 0.000000000000 -4513.105960000000 -24.616924300000 1968.479370000000 3 48 60 3762.000000000000 0.000000000000 0.000000000000 0.000000000000 5968.624510000000 -1186.822020000000 0.000000000000 3762.000000000000 0.000000000000 -5968.624510000000 0.000000000000 50.663265200000 0.000000000000 0.000000000000 3762.000000000000 1186.822020000000 -50.663265200000 0.000000000000 0.000000000000 -5968.624510000000 1186.822020000000 10317.561500000000 -11.732527700000 -90.086982700000 5968.624510000000 0.000000000000 -50.663265200000 -11.732527700000 10534.640600000001 -1893.414430000000 -1186.822020000000 50.663265200000 0.000000000000 -90.086982700000 -1893.414430000000 1058.437260000000 3 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8406.970700000000 -1357.630130000000 0.000000000000 5000.000000000000 0.000000000000 -8406.970700000000 0.000000000000 755.064270000000 0.000000000000 0.000000000000 5000.000000000000 1357.630130000000 -755.064270000000 0.000000000000 0.000000000000 -8406.970700000000 1357.630130000000 15367.149400000000 -55.559997600000 -1265.171260000000 8406.970700000000 0.000000000000 -755.064270000000 -55.559997600000 15909.534200000000 -2307.068850000000 -1357.630130000000 755.064270000000 0.000000000000 -1265.171260000000 -2307.068850000000 1550.956670000000 4 8 60 3556.000000000000 0.000000000000 0.000000000000 0.000000000000 8885.078130000000 1699.066280000000 0.000000000000 3556.000000000000 0.000000000000 -8885.078130000000 0.000000000000 -4358.130370000000 0.000000000000 0.000000000000 3556.000000000000 -1699.066280000000 4358.130370000000 0.000000000000 0.000000000000 -8885.078130000000 -1699.066280000000 23612.517599999999 -2156.747310000000 10924.941400000000 8885.078130000000 0.000000000000 4358.130370000000 -2156.747310000000 27708.873000000000 4317.427250000000 1699.066280000000 -4358.130370000000 0.000000000000 10924.941400000000 4317.427250000000 6781.291500000000 4 30 60 3443.000000000000 0.000000000000 0.000000000000 0.000000000000 6485.799800000000 -535.357361000000 0.000000000000 3443.000000000000 0.000000000000 -6485.799800000000 0.000000000000 1355.497800000000 0.000000000000 0.000000000000 3443.000000000000 535.357361000000 -1355.497800000000 0.000000000000 0.000000000000 -6485.799800000000 535.357361000000 12790.953100000001 -42.601730300000 -2581.947750000000 6485.799800000000 0.000000000000 -1355.497800000000 -42.601730300000 13095.614299999999 -921.442627000000 -535.357361000000 1355.497800000000 0.000000000000 -2581.947750000000 -921.442627000000 1153.933470000000 4 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10939.819299999999 107.455582000000 0.000000000000 5000.000000000000 0.000000000000 -10939.819299999999 0.000000000000 -587.201538000000 0.000000000000 0.000000000000 5000.000000000000 -107.455582000000 587.201538000000 0.000000000000 0.000000000000 -10939.819299999999 -107.455582000000 25787.550800000001 516.525513000000 832.283936000000 10939.819299999999 0.000000000000 587.201538000000 516.525513000000 26321.871100000000 942.351624000000 107.455582000000 -587.201538000000 0.000000000000 832.283936000000 942.351624000000 2014.884890000000 4 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12282.943400000000 1456.491210000000 0.000000000000 5000.000000000000 0.000000000000 -12282.943400000000 0.000000000000 625.419067000000 0.000000000000 0.000000000000 5000.000000000000 -1456.491210000000 -625.419067000000 0.000000000000 0.000000000000 -12282.943400000000 -1456.491210000000 33063.074200000003 317.783875000000 -1511.834720000000 12282.943400000000 0.000000000000 -625.419067000000 317.783875000000 32319.980500000001 4600.546880000000 1456.491210000000 625.419067000000 0.000000000000 -1511.834720000000 4600.546880000000 2100.769530000000 4 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10977.705099999999 125.830894000000 0.000000000000 5000.000000000000 0.000000000000 -10977.705099999999 0.000000000000 -295.208710000000 0.000000000000 0.000000000000 5000.000000000000 -125.830894000000 295.208710000000 0.000000000000 0.000000000000 -10977.705099999999 -125.830894000000 25846.480500000001 476.967499000000 304.752869000000 10977.705099999999 0.000000000000 295.208710000000 476.967499000000 26369.437500000000 946.852051000000 125.830894000000 -295.208710000000 0.000000000000 304.752869000000 946.852051000000 1911.877200000000 4 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9700.719730000001 -700.159485000000 0.000000000000 5000.000000000000 0.000000000000 -9700.719730000001 0.000000000000 -745.116089000000 0.000000000000 0.000000000000 5000.000000000000 700.159485000000 745.116089000000 0.000000000000 0.000000000000 -9700.719730000001 700.159485000000 19602.744100000000 170.600571000000 1321.248170000000 9700.719730000001 0.000000000000 745.116089000000 170.600571000000 20264.705099999999 -1255.188840000000 -700.159485000000 -745.116089000000 0.000000000000 1321.248170000000 -1255.188840000000 1240.055180000000 4 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10221.757799999999 -147.288025000000 0.000000000000 5000.000000000000 0.000000000000 -10221.757799999999 0.000000000000 142.862625000000 0.000000000000 0.000000000000 5000.000000000000 147.288025000000 -142.862625000000 0.000000000000 0.000000000000 -10221.757799999999 147.288025000000 21779.884800000000 108.346840000000 -367.342010000000 10221.757799999999 0.000000000000 -142.862625000000 108.346840000000 22391.994100000000 -42.200862900000 -147.288025000000 142.862625000000 0.000000000000 -367.342010000000 -42.200862900000 1169.380250000000 5 8 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12283.743200000001 1023.305050000000 0.000000000000 5000.000000000000 0.000000000000 -12283.743200000001 0.000000000000 -5710.894530000000 0.000000000000 0.000000000000 5000.000000000000 -1023.305050000000 5710.894530000000 0.000000000000 0.000000000000 -12283.743200000001 -1023.305050000000 31355.169900000001 -1090.540040000000 14081.906300000001 12283.743200000001 0.000000000000 5710.894530000000 -1090.540040000000 37080.906300000002 2567.129880000000 1023.305050000000 -5710.894530000000 0.000000000000 14081.906300000001 2567.129880000000 7871.087400000000 5 37 60 2637.000000000000 0.000000000000 0.000000000000 0.000000000000 6440.671390000000 -262.045563000000 0.000000000000 2637.000000000000 0.000000000000 -6440.671390000000 0.000000000000 -3208.239010000000 0.000000000000 0.000000000000 2637.000000000000 262.045563000000 3208.239010000000 0.000000000000 0.000000000000 -6440.671390000000 262.045563000000 16039.489299999999 296.089203000000 7861.519530000000 6440.671390000000 0.000000000000 3208.239010000000 296.089203000000 19783.365200000000 -605.788574000000 -262.045563000000 -3208.239010000000 0.000000000000 7861.519530000000 -605.788574000000 4274.469730000000 5 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10650.571300000000 -372.124878000000 0.000000000000 5000.000000000000 0.000000000000 -10650.571300000000 0.000000000000 813.583191000000 0.000000000000 0.000000000000 5000.000000000000 372.124878000000 -813.583191000000 0.000000000000 0.000000000000 -10650.571300000000 372.124878000000 24137.027300000002 301.377838000000 -2241.588130000000 10650.571300000000 0.000000000000 -813.583191000000 301.377838000000 25061.460899999998 -305.805969000000 -372.124878000000 813.583191000000 0.000000000000 -2241.588130000000 -305.805969000000 1681.250610000000 5 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12323.435500000000 968.414429000000 0.000000000000 5000.000000000000 0.000000000000 -12323.435500000000 0.000000000000 2029.188720000000 0.000000000000 0.000000000000 5000.000000000000 -968.414429000000 -2029.188720000000 0.000000000000 0.000000000000 -12323.435500000000 -968.414429000000 33148.480499999998 767.406006000000 -5262.147460000000 12323.435500000000 0.000000000000 -2029.188720000000 767.406006000000 32884.199200000003 3395.408940000000 968.414429000000 2029.188720000000 0.000000000000 -5262.147460000000 3395.408940000000 2688.098630000000 5 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10951.529300000000 -181.630417000000 0.000000000000 5000.000000000000 0.000000000000 -10951.529300000000 0.000000000000 1236.284910000000 0.000000000000 0.000000000000 5000.000000000000 181.630417000000 -1236.284910000000 0.000000000000 0.000000000000 -10951.529300000000 181.630417000000 25515.591799999998 326.034973000000 -3195.971440000000 10951.529300000000 0.000000000000 -1236.284910000000 326.034973000000 26538.328099999999 145.615463000000 -181.630417000000 1236.284910000000 0.000000000000 -3195.971440000000 145.615463000000 1839.181880000000 5 48 60 3767.000000000000 0.000000000000 0.000000000000 0.000000000000 6764.515630000000 -962.202393000000 0.000000000000 3767.000000000000 0.000000000000 -6764.515630000000 0.000000000000 130.440277000000 0.000000000000 0.000000000000 3767.000000000000 962.202393000000 -130.440277000000 0.000000000000 0.000000000000 -6764.515630000000 962.202393000000 12741.493200000001 3.873766900000 -371.209625000000 6764.515630000000 0.000000000000 -130.440277000000 3.873766900000 13074.217800000000 -1680.321290000000 -962.202393000000 130.440277000000 0.000000000000 -371.209625000000 -1680.321290000000 895.316284000000 5 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9931.441409999999 -883.767090000000 0.000000000000 5000.000000000000 0.000000000000 -9931.441409999999 0.000000000000 984.418396000000 0.000000000000 0.000000000000 5000.000000000000 883.767090000000 -984.418396000000 0.000000000000 0.000000000000 -9931.441409999999 883.767090000000 20584.496100000000 -10.866478000000 -2076.685300000000 9931.441409999999 0.000000000000 -984.418396000000 -10.866478000000 21452.228500000001 -1622.549440000000 -883.767090000000 984.418396000000 0.000000000000 -2076.685300000000 -1622.549440000000 1360.744020000000 6 8 60 4363.000000000000 0.000000000000 0.000000000000 0.000000000000 10143.815399999999 -2004.166020000000 0.000000000000 4363.000000000000 0.000000000000 -10143.815399999999 0.000000000000 -4494.586910000000 0.000000000000 0.000000000000 4363.000000000000 2004.166020000000 4494.586910000000 0.000000000000 0.000000000000 -10143.815399999999 2004.166020000000 24879.429700000001 2063.251220000000 10476.687500000000 10143.815399999999 0.000000000000 4494.586910000000 2063.251220000000 28527.685500000000 -4638.044430000000 -2004.166020000000 -4494.586910000000 0.000000000000 10476.687500000000 -4638.044430000000 6124.472660000000 6 40 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12129.556600000000 -2866.313230000000 0.000000000000 5000.000000000000 0.000000000000 -12129.556600000000 0.000000000000 1460.265500000000 0.000000000000 0.000000000000 5000.000000000000 2866.313230000000 -1460.265500000000 0.000000000000 0.000000000000 -12129.556600000000 2866.313230000000 31886.248000000000 -737.943176000000 -3664.112790000000 12129.556600000000 0.000000000000 -1460.265500000000 -737.943176000000 31725.330099999999 -6724.838380000000 -2866.313230000000 1460.265500000000 0.000000000000 -3664.112790000000 -6724.838380000000 3616.684810000000 6 41 60 3790.000000000000 0.000000000000 0.000000000000 0.000000000000 8621.522460000000 -2168.457520000000 0.000000000000 3790.000000000000 0.000000000000 -8621.522460000000 0.000000000000 2113.239500000000 0.000000000000 0.000000000000 3790.000000000000 2168.457520000000 -2113.239500000000 0.000000000000 0.000000000000 -8621.522460000000 2168.457520000000 21249.060500000000 -1041.591310000000 -4929.360840000000 8621.522460000000 0.000000000000 -2113.239500000000 -1041.591310000000 21827.839800000002 -4819.820310000000 -2168.457520000000 2113.239500000000 0.000000000000 -4929.360840000000 -4819.820310000000 3319.970950000000 6 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12712.269500000000 270.256622000000 0.000000000000 5000.000000000000 0.000000000000 -12712.269500000000 0.000000000000 3563.292240000000 0.000000000000 0.000000000000 5000.000000000000 -270.256622000000 -3563.292240000000 0.000000000000 0.000000000000 -12712.269500000000 -270.256622000000 35195.937500000000 563.538147000000 -9130.772460000000 12712.269500000000 0.000000000000 -3563.292240000000 563.538147000000 35717.496099999997 1194.518070000000 270.256622000000 3563.292240000000 0.000000000000 -9130.772460000000 1194.518070000000 5432.891600000000 6 47 60 4023.000000000000 0.000000000000 0.000000000000 0.000000000000 9294.114260000000 -2247.892090000000 0.000000000000 4023.000000000000 0.000000000000 -9294.114260000000 0.000000000000 2341.234620000000 0.000000000000 0.000000000000 4023.000000000000 2247.892090000000 -2341.234620000000 0.000000000000 0.000000000000 -9294.114260000000 2247.892090000000 23193.775399999999 -1124.459720000000 -5567.887210000000 9294.114260000000 0.000000000000 -2341.234620000000 -1124.459720000000 23901.306600000000 -5049.509280000000 -2247.892090000000 2341.234620000000 0.000000000000 -5567.887210000000 -5049.509280000000 3524.676510000000 7 8 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12076.506799999999 -713.634460000000 0.000000000000 5000.000000000000 0.000000000000 -12076.506799999999 0.000000000000 -4227.548340000000 0.000000000000 0.000000000000 5000.000000000000 713.634460000000 4227.548340000000 0.000000000000 0.000000000000 -12076.506799999999 713.634460000000 30593.041000000001 458.115387000000 10287.245100000000 12076.506799999999 0.000000000000 4227.548340000000 458.115387000000 33288.562500000000 -1567.663090000000 -713.634460000000 -4227.548340000000 0.000000000000 10287.245100000000 -1567.663090000000 5222.935060000000 7 37 60 4516.000000000000 0.000000000000 0.000000000000 0.000000000000 10789.234399999999 -2000.508300000000 0.000000000000 4516.000000000000 0.000000000000 -10789.234399999999 0.000000000000 -4509.996090000000 0.000000000000 0.000000000000 4516.000000000000 2000.508300000000 4509.996090000000 0.000000000000 0.000000000000 -10789.234399999999 2000.508300000000 27307.956999999999 1921.707760000000 10755.733399999999 10789.234399999999 0.000000000000 4509.996090000000 1921.707760000000 30696.947300000000 -4663.515630000000 -2000.508300000000 -4509.996090000000 0.000000000000 10755.733399999999 -4663.515630000000 6107.746580000000 7 40 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11556.375000000000 -766.241150000000 0.000000000000 5000.000000000000 0.000000000000 -11556.375000000000 0.000000000000 2324.088620000000 0.000000000000 0.000000000000 5000.000000000000 766.241150000000 -2324.088620000000 0.000000000000 0.000000000000 -11556.375000000000 766.241150000000 28767.267599999999 42.864212000000 -5890.663090000000 11556.375000000000 0.000000000000 -2324.088620000000 42.864212000000 30033.033200000002 -1034.061280000000 -766.241150000000 2324.088620000000 0.000000000000 -5890.663090000000 -1034.061280000000 2742.806880000000 7 41 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10151.109399999999 -1396.527340000000 0.000000000000 5000.000000000000 0.000000000000 -10151.109399999999 0.000000000000 2246.861330000000 0.000000000000 0.000000000000 5000.000000000000 1396.527340000000 -2246.861330000000 0.000000000000 0.000000000000 -10151.109399999999 1396.527340000000 22177.869100000000 -424.899017000000 -5053.049800000000 10151.109399999999 0.000000000000 -2246.861330000000 -424.899017000000 23409.507799999999 -2531.224370000000 -1396.527340000000 2246.861330000000 0.000000000000 -5053.049800000000 -2531.224370000000 2340.157230000000 7 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11095.127899999999 -722.200378000000 0.000000000000 5000.000000000000 0.000000000000 -11095.127899999999 0.000000000000 3445.874760000000 0.000000000000 0.000000000000 5000.000000000000 722.200378000000 -3445.874760000000 0.000000000000 0.000000000000 -11095.127899999999 722.200378000000 26368.343799999999 -184.702347000000 -8078.700200000000 11095.127899999999 0.000000000000 -3445.874760000000 -184.702347000000 28412.390599999999 -1019.434270000000 -722.200378000000 3445.874760000000 0.000000000000 -8078.700200000000 -1019.434270000000 3465.046140000000 7 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10537.081099999999 -1287.359380000000 0.000000000000 5000.000000000000 0.000000000000 -10537.081099999999 0.000000000000 2535.036380000000 0.000000000000 0.000000000000 5000.000000000000 1287.359380000000 -2535.036380000000 0.000000000000 0.000000000000 -10537.081099999999 1287.359380000000 23674.363300000001 -455.593292000000 -5774.134770000000 10537.081099999999 0.000000000000 -2535.036380000000 -455.593292000000 25198.234400000001 -2401.820310000000 -1287.359380000000 2535.036380000000 0.000000000000 -5774.134770000000 -2401.820310000000 2549.379640000000 7 49 60 3964.000000000000 0.000000000000 0.000000000000 0.000000000000 6992.566410000000 -1572.631100000000 0.000000000000 3964.000000000000 0.000000000000 -6992.566410000000 0.000000000000 1130.104980000000 0.000000000000 0.000000000000 3964.000000000000 1572.631100000000 -1130.104980000000 0.000000000000 0.000000000000 -6992.566410000000 1572.631100000000 13477.401400000001 -427.098907000000 -2083.332280000000 6992.566410000000 0.000000000000 -1130.104980000000 -427.098907000000 13520.273400000000 -2714.761720000000 -1572.631100000000 1130.104980000000 0.000000000000 -2083.332280000000 -2714.761720000000 1326.183720000000 8 10 60 3948.000000000000 0.000000000000 0.000000000000 0.000000000000 8901.966800000000 1696.447630000000 0.000000000000 3948.000000000000 0.000000000000 -8901.966800000000 0.000000000000 -4454.375980000000 0.000000000000 0.000000000000 3948.000000000000 -1696.447630000000 4454.375980000000 0.000000000000 0.000000000000 -8901.966800000000 -1696.447630000000 21231.728500000001 -1714.497800000000 10170.534200000000 8901.966800000000 0.000000000000 4454.375980000000 -1714.497800000000 25449.357400000001 3671.284910000000 1696.447630000000 -4454.375980000000 0.000000000000 10170.534200000000 3671.284910000000 6373.593260000000 8 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11626.129900000000 1224.138920000000 0.000000000000 5000.000000000000 0.000000000000 -11626.129900000000 0.000000000000 -5584.405760000000 0.000000000000 0.000000000000 5000.000000000000 -1224.138920000000 5584.405760000000 0.000000000000 0.000000000000 -11626.129900000000 -1224.138920000000 27868.333999999999 -1290.235470000000 13055.112300000001 11626.129900000000 0.000000000000 5584.405760000000 -1290.235470000000 33523.726600000002 2675.259030000000 1224.138920000000 -5584.405760000000 0.000000000000 13055.112300000001 2675.259030000000 7174.617680000000 8 33 60 3601.000000000000 0.000000000000 0.000000000000 0.000000000000 8228.267580000000 1119.819460000000 0.000000000000 3601.000000000000 0.000000000000 -8228.267580000000 0.000000000000 -4641.676270000000 0.000000000000 0.000000000000 3601.000000000000 -1119.819460000000 4641.676270000000 0.000000000000 0.000000000000 -8228.267580000000 -1119.819460000000 19665.115200000000 -1445.133910000000 10601.315399999999 8228.267580000000 0.000000000000 4641.676270000000 -1445.133910000000 24907.083999999999 2518.959720000000 1119.819460000000 -4641.676270000000 0.000000000000 10601.315399999999 2518.959720000000 6852.838380000000 8 39 60 1655.000000000000 0.000000000000 0.000000000000 0.000000000000 2709.440920000000 -37.290256500000 0.000000000000 1655.000000000000 0.000000000000 -2709.440920000000 0.000000000000 934.405579000000 0.000000000000 0.000000000000 1655.000000000000 37.290256500000 -934.405579000000 0.000000000000 0.000000000000 -2709.440920000000 37.290256500000 4567.070310000000 9.178101540000 -1533.558840000000 2709.440920000000 0.000000000000 -934.405579000000 9.178101540000 5039.965330000000 -19.648798000000 -37.290256500000 934.405579000000 0.000000000000 -1533.558840000000 -19.648798000000 646.464539000000 8 40 60 2396.000000000000 0.000000000000 0.000000000000 0.000000000000 3880.177000000000 -210.285965000000 0.000000000000 2396.000000000000 0.000000000000 -3880.177000000000 0.000000000000 1284.593630000000 0.000000000000 0.000000000000 2396.000000000000 210.285965000000 -1284.593630000000 0.000000000000 0.000000000000 -3880.177000000000 210.285965000000 6467.594730000000 -79.520340000000 -2079.727780000000 3880.177000000000 0.000000000000 -1284.593630000000 -79.520340000000 7065.126460000000 -300.672546000000 -210.285965000000 1284.593630000000 0.000000000000 -2079.727780000000 -300.672546000000 857.453308000000 8 46 60 2292.000000000000 0.000000000000 0.000000000000 0.000000000000 3889.952880000000 380.894958000000 0.000000000000 2292.000000000000 0.000000000000 -3889.952880000000 0.000000000000 1293.823970000000 0.000000000000 0.000000000000 2292.000000000000 -380.894958000000 -1293.823970000000 0.000000000000 0.000000000000 -3889.952880000000 -380.894958000000 6972.200680000000 247.975983000000 -2194.227780000000 3889.952880000000 0.000000000000 -1293.823970000000 247.975983000000 7458.500980000000 739.631836000000 380.894958000000 1293.823970000000 0.000000000000 -2194.227780000000 739.631836000000 1081.862430000000 9 12 60 3527.000000000000 0.000000000000 0.000000000000 0.000000000000 7223.109860000000 1820.697750000000 0.000000000000 3527.000000000000 0.000000000000 -7223.109860000000 0.000000000000 -3854.746340000000 0.000000000000 0.000000000000 3527.000000000000 -1820.697750000000 3854.746340000000 0.000000000000 0.000000000000 -7223.109860000000 -1820.697750000000 16023.999000000000 -1930.516720000000 7787.032710000000 7223.109860000000 0.000000000000 3854.746340000000 -1930.516720000000 19405.878900000000 3727.246830000000 1820.697750000000 -3854.746340000000 0.000000000000 7787.032710000000 3727.246830000000 5615.269530000000 9 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9574.002930000001 353.267151000000 0.000000000000 5000.000000000000 0.000000000000 -9574.002930000001 0.000000000000 -1034.251100000000 0.000000000000 0.000000000000 5000.000000000000 -353.267151000000 1034.251100000000 0.000000000000 0.000000000000 -9574.002930000001 -353.267151000000 19170.312500000000 6.283476830000 2245.782710000000 9574.002930000001 0.000000000000 1034.251100000000 6.283476830000 19123.216799999998 450.684235000000 353.267151000000 -1034.251100000000 0.000000000000 2245.782710000000 450.684235000000 957.691223000000 9 33 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9799.574220000000 76.793418900000 0.000000000000 5000.000000000000 0.000000000000 -9799.574220000000 0.000000000000 -2598.777830000000 0.000000000000 0.000000000000 5000.000000000000 -76.793418900000 2598.777830000000 0.000000000000 0.000000000000 -9799.574220000000 -76.793418900000 20345.324199999999 296.173065000000 5098.280760000000 9799.574220000000 0.000000000000 2598.777830000000 296.173065000000 21132.152300000002 134.383041000000 76.793418900000 -2598.777830000000 0.000000000000 5098.280760000000 134.383041000000 2707.634280000000 10 32 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7905.354980000000 399.287415000000 0.000000000000 5000.000000000000 0.000000000000 -7905.354980000000 0.000000000000 1089.712890000000 0.000000000000 0.000000000000 5000.000000000000 -399.287415000000 -1089.712890000000 0.000000000000 0.000000000000 -7905.354980000000 -399.287415000000 14500.253900000000 79.771232600000 -1577.039310000000 7905.354980000000 0.000000000000 -1089.712890000000 79.771232600000 13812.017599999999 164.608566000000 399.287415000000 1089.712890000000 0.000000000000 -1577.039310000000 164.608566000000 1991.198000000000 10 33 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8274.544920000000 1019.665280000000 0.000000000000 5000.000000000000 0.000000000000 -8274.544920000000 0.000000000000 950.547119000000 0.000000000000 0.000000000000 5000.000000000000 -1019.665280000000 -950.547119000000 0.000000000000 0.000000000000 -8274.544920000000 -1019.665280000000 15754.739299999999 652.048340000000 -1432.148190000000 8274.544920000000 0.000000000000 -950.547119000000 652.048340000000 14560.248000000000 1407.768680000000 1019.665280000000 950.547119000000 0.000000000000 -1432.148190000000 1407.768680000000 2364.013670000000 10 35 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7874.096190000000 -631.027466000000 0.000000000000 5000.000000000000 0.000000000000 -7874.096190000000 0.000000000000 736.159912000000 0.000000000000 0.000000000000 5000.000000000000 631.027466000000 -736.159912000000 0.000000000000 0.000000000000 -7874.096190000000 631.027466000000 13794.600600000000 188.497498000000 -869.550964000000 7874.096190000000 0.000000000000 -736.159912000000 188.497498000000 13778.099600000000 -1199.433470000000 -631.027466000000 736.159912000000 0.000000000000 -869.550964000000 -1199.433470000000 1474.660280000000 10 36 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8224.656250000000 -299.479858000000 0.000000000000 5000.000000000000 0.000000000000 -8224.656250000000 0.000000000000 1260.318970000000 0.000000000000 0.000000000000 5000.000000000000 299.479858000000 -1260.318970000000 0.000000000000 0.000000000000 -8224.656250000000 299.479858000000 15363.536099999999 67.282562300000 -1736.381230000000 8224.656250000000 0.000000000000 -1260.318970000000 67.282562300000 15120.170899999999 -842.988464000000 -299.479858000000 1260.318970000000 0.000000000000 -1736.381230000000 -842.988464000000 1136.320800000000 11 32 60 4419.000000000000 0.000000000000 0.000000000000 0.000000000000 6749.575680000000 155.875977000000 0.000000000000 4419.000000000000 0.000000000000 -6749.575680000000 0.000000000000 897.638977000000 0.000000000000 0.000000000000 4419.000000000000 -155.875977000000 -897.638977000000 0.000000000000 0.000000000000 -6749.575680000000 -155.875977000000 11510.538100000000 102.124939000000 -1244.351930000000 6749.575680000000 0.000000000000 -897.638977000000 102.124939000000 11587.610400000000 455.187225000000 155.875977000000 897.638977000000 0.000000000000 -1244.351930000000 455.187225000000 1529.151000000000 11 33 60 4590.000000000000 0.000000000000 0.000000000000 0.000000000000 7792.536130000000 -72.036010700000 0.000000000000 4590.000000000000 0.000000000000 -7792.536130000000 0.000000000000 1313.373540000000 0.000000000000 0.000000000000 4590.000000000000 72.036010700000 -1313.373540000000 0.000000000000 0.000000000000 -7792.536130000000 72.036010700000 14078.054700000001 18.910303100000 -2196.497070000000 7792.536130000000 0.000000000000 -1313.373540000000 18.910303100000 13827.929700000001 -57.745662700000 -72.036010700000 1313.373540000000 0.000000000000 -2196.497070000000 -57.745662700000 1020.221310000000 11 35 60 3336.000000000000 0.000000000000 0.000000000000 0.000000000000 4992.840820000000 -1267.329710000000 0.000000000000 3336.000000000000 0.000000000000 -4992.840820000000 0.000000000000 670.044739000000 0.000000000000 0.000000000000 3336.000000000000 1267.329710000000 -670.044739000000 0.000000000000 0.000000000000 -4992.840820000000 1267.329710000000 8417.025390000001 -251.547775000000 -899.018066000000 4992.840820000000 0.000000000000 -670.044739000000 -251.547775000000 8298.266600000001 -1995.937990000000 -1267.329710000000 670.044739000000 0.000000000000 -899.018066000000 -1995.937990000000 1119.784060000000 11 36 60 3822.000000000000 0.000000000000 0.000000000000 0.000000000000 5635.988280000000 -1262.534420000000 0.000000000000 3822.000000000000 0.000000000000 -5635.988280000000 0.000000000000 1150.904050000000 0.000000000000 0.000000000000 3822.000000000000 1262.534420000000 -1150.904050000000 0.000000000000 0.000000000000 -5635.988280000000 1262.534420000000 9462.507809999999 -318.667389000000 -1581.702030000000 5635.988280000000 0.000000000000 -1150.904050000000 -318.667389000000 9176.409180000001 -2055.787350000000 -1262.534420000000 1150.904050000000 0.000000000000 -1581.702030000000 -2055.787350000000 1076.583860000000 12 13 60 2579.000000000000 0.000000000000 0.000000000000 0.000000000000 3893.920900000000 -275.587433000000 0.000000000000 2579.000000000000 0.000000000000 -3893.920900000000 0.000000000000 -1927.766240000000 0.000000000000 0.000000000000 2579.000000000000 275.587433000000 1927.766240000000 0.000000000000 0.000000000000 -3893.920900000000 275.587433000000 6065.505860000000 243.237228000000 2895.694580000000 3893.920900000000 0.000000000000 1927.766240000000 243.237228000000 7472.352050000000 -427.896149000000 -275.587433000000 -1927.766240000000 0.000000000000 2895.694580000000 -427.896149000000 1718.369380000000 12 14 60 1396.000000000000 0.000000000000 0.000000000000 0.000000000000 2090.340090000000 -274.684998000000 0.000000000000 1396.000000000000 0.000000000000 -2090.340090000000 0.000000000000 -1155.071040000000 0.000000000000 0.000000000000 1396.000000000000 274.684998000000 1155.071040000000 0.000000000000 0.000000000000 -2090.340090000000 274.684998000000 3244.400390000000 266.179138000000 1739.630000000000 2090.340090000000 0.000000000000 1155.071040000000 266.179138000000 4147.152340000000 -417.789948000000 -274.684998000000 -1155.071040000000 0.000000000000 1739.630000000000 -417.789948000000 1127.582030000000 12 32 60 1595.000000000000 0.000000000000 0.000000000000 0.000000000000 2337.862060000000 112.305550000000 0.000000000000 1595.000000000000 0.000000000000 -2337.862060000000 0.000000000000 -330.489410000000 0.000000000000 0.000000000000 1595.000000000000 -112.305550000000 330.489410000000 0.000000000000 0.000000000000 -2337.862060000000 -112.305550000000 3619.297120000000 47.709995300000 493.602783000000 2337.862060000000 0.000000000000 330.489410000000 47.709995300000 4240.059080000000 158.339569000000 112.305550000000 -330.489410000000 0.000000000000 493.602783000000 158.339569000000 985.095398000000 12 33 60 2727.000000000000 0.000000000000 0.000000000000 0.000000000000 3856.676760000000 27.251403800000 0.000000000000 2727.000000000000 0.000000000000 -3856.676760000000 0.000000000000 74.868499800000 0.000000000000 0.000000000000 2727.000000000000 -27.251403800000 -74.868499800000 0.000000000000 0.000000000000 -3856.676760000000 -27.251403800000 5732.583500000000 112.821930000000 15.282605200000 3856.676760000000 0.000000000000 -74.868499800000 112.821930000000 6950.547360000000 32.477577200000 27.251403800000 74.868499800000 0.000000000000 15.282605200000 32.477577200000 1724.072140000000 12 35 60 1771.000000000000 0.000000000000 0.000000000000 0.000000000000 2553.118900000000 -478.726746000000 0.000000000000 1771.000000000000 0.000000000000 -2553.118900000000 0.000000000000 -324.592010000000 0.000000000000 0.000000000000 1771.000000000000 478.726746000000 324.592010000000 0.000000000000 0.000000000000 -2553.118900000000 478.726746000000 3906.943850000000 -14.392703100000 540.404907000000 2553.118900000000 0.000000000000 324.592010000000 -14.392703100000 4733.678710000000 -689.748108000000 -478.726746000000 -324.592010000000 0.000000000000 540.404907000000 -689.748108000000 1228.951780000000 13 17 60 1650.000000000000 0.000000000000 0.000000000000 0.000000000000 4029.826900000000 -175.957565000000 0.000000000000 1650.000000000000 0.000000000000 -4029.826900000000 0.000000000000 -1468.001830000000 0.000000000000 0.000000000000 1650.000000000000 175.957565000000 1468.001830000000 0.000000000000 0.000000000000 -4029.826900000000 175.957565000000 10080.332000000000 140.453918000000 3646.044430000000 4029.826900000000 0.000000000000 1468.001830000000 140.453918000000 11384.630900000000 -367.599670000000 -175.957565000000 -1468.001830000000 0.000000000000 3646.044430000000 -367.599670000000 1429.310670000000 13 18 60 2386.000000000000 0.000000000000 0.000000000000 0.000000000000 6434.395510000000 -21.810899700000 0.000000000000 2386.000000000000 0.000000000000 -6434.395510000000 0.000000000000 -2737.027590000000 0.000000000000 0.000000000000 2386.000000000000 21.810899700000 2737.027590000000 0.000000000000 0.000000000000 -6434.395510000000 21.810899700000 17540.166000000001 10.410425200000 7434.240720000000 6434.395510000000 0.000000000000 2737.027590000000 10.410425200000 20744.390599999999 -7.680490020000 -21.810899700000 -2737.027590000000 0.000000000000 7434.240720000000 -7.680490020000 3406.829830000000 13 19 60 2131.000000000000 0.000000000000 0.000000000000 0.000000000000 5833.907230000000 34.406391100000 0.000000000000 2131.000000000000 0.000000000000 -5833.907230000000 0.000000000000 -2530.966060000000 0.000000000000 0.000000000000 2131.000000000000 -34.406391100000 2530.966060000000 0.000000000000 0.000000000000 -5833.907230000000 -34.406391100000 16099.826200000000 -49.173893000000 6944.542970000000 5833.907230000000 0.000000000000 2530.966060000000 -49.173893000000 19132.982400000001 135.468597000000 34.406391100000 -2530.966060000000 0.000000000000 6944.542970000000 135.468597000000 3181.456540000000 13 23 60 1444.000000000000 0.000000000000 0.000000000000 0.000000000000 3913.425290000000 -155.631393000000 0.000000000000 1444.000000000000 0.000000000000 -3913.425290000000 0.000000000000 -1750.059200000000 0.000000000000 0.000000000000 1444.000000000000 155.631393000000 1750.059200000000 0.000000000000 0.000000000000 -3913.425290000000 155.631393000000 10684.366200000000 198.508087000000 4745.888180000000 3913.425290000000 0.000000000000 1750.059200000000 198.508087000000 12802.882799999999 -410.500366000000 -155.631393000000 -1750.059200000000 0.000000000000 4745.888180000000 -410.500366000000 2234.380130000000 13 54 60 3326.000000000000 0.000000000000 0.000000000000 0.000000000000 9220.417970000000 429.479126000000 0.000000000000 3326.000000000000 0.000000000000 -9220.417970000000 0.000000000000 -3376.755860000000 0.000000000000 0.000000000000 3326.000000000000 -429.479126000000 3376.755860000000 0.000000000000 0.000000000000 -9220.417970000000 -429.479126000000 25826.480500000001 -428.619904000000 9379.635740000000 9220.417970000000 0.000000000000 3376.755860000000 -428.619904000000 29296.099600000001 1229.441160000000 429.479126000000 -3376.755860000000 0.000000000000 9379.635740000000 1229.441160000000 3766.867680000000 13 55 60 4425.000000000000 0.000000000000 0.000000000000 0.000000000000 12013.814500000000 492.333160000000 0.000000000000 4425.000000000000 0.000000000000 -12013.814500000000 0.000000000000 -4453.944340000000 0.000000000000 0.000000000000 4425.000000000000 -492.333160000000 4453.944340000000 0.000000000000 0.000000000000 -12013.814500000000 -492.333160000000 33245.175799999997 -582.983154000000 12256.255900000000 12013.814500000000 0.000000000000 4453.944340000000 -582.983154000000 37762.312500000000 1511.409420000000 492.333160000000 -4453.944340000000 0.000000000000 12256.255900000000 1511.409420000000 5029.117190000000 13 56 60 4084.000000000000 0.000000000000 0.000000000000 0.000000000000 11247.710900000000 260.064514000000 0.000000000000 4084.000000000000 0.000000000000 -11247.710900000000 0.000000000000 -4354.687990000000 0.000000000000 0.000000000000 4084.000000000000 -260.064514000000 4354.687990000000 0.000000000000 0.000000000000 -11247.710900000000 -260.064514000000 31389.931600000000 -329.186035000000 12074.047900000000 11247.710900000000 0.000000000000 4354.687990000000 -329.186035000000 36136.937500000000 849.132935000000 260.064514000000 -4354.687990000000 0.000000000000 12074.047900000000 849.132935000000 5037.974120000000 13 57 60 4316.000000000000 0.000000000000 0.000000000000 0.000000000000 11716.536099999999 254.294937000000 0.000000000000 4316.000000000000 0.000000000000 -11716.536099999999 0.000000000000 -4408.353520000000 0.000000000000 0.000000000000 4316.000000000000 -254.294937000000 4408.353520000000 0.000000000000 0.000000000000 -11716.536099999999 -254.294937000000 32289.119100000000 -318.626526000000 12071.934600000001 11716.536099999999 0.000000000000 4408.353520000000 -318.626526000000 36886.167999999998 843.555969000000 254.294937000000 -4408.353520000000 0.000000000000 12071.934600000001 843.555969000000 4904.716800000000 13 58 60 2802.000000000000 0.000000000000 0.000000000000 0.000000000000 7448.922850000000 249.053299000000 0.000000000000 2802.000000000000 0.000000000000 -7448.922850000000 0.000000000000 -2503.925540000000 0.000000000000 0.000000000000 2802.000000000000 -249.053299000000 2503.925540000000 0.000000000000 0.000000000000 -7448.922850000000 -249.053299000000 20034.298800000000 -252.186737000000 6735.719730000000 7448.922850000000 0.000000000000 2503.925540000000 -252.186737000000 22387.166000000001 713.145081000000 249.053299000000 -2503.925540000000 0.000000000000 6735.719730000000 713.145081000000 2578.366700000000 14 17 60 4629.000000000000 0.000000000000 0.000000000000 0.000000000000 10677.064500000000 203.985168000000 0.000000000000 4629.000000000000 0.000000000000 -10677.064500000000 0.000000000000 317.561584000000 0.000000000000 0.000000000000 4629.000000000000 -203.985168000000 -317.561584000000 0.000000000000 0.000000000000 -10677.064500000000 -203.985168000000 25384.310500000000 90.312767000000 -720.954651000000 10677.064500000000 0.000000000000 -317.561584000000 90.312767000000 25305.130900000000 684.323669000000 203.985168000000 317.561584000000 0.000000000000 -720.954651000000 684.323669000000 398.825714000000 14 18 60 4659.000000000000 0.000000000000 0.000000000000 0.000000000000 11668.033200000000 858.145569000000 0.000000000000 4659.000000000000 0.000000000000 -11668.033200000000 0.000000000000 -109.749908000000 0.000000000000 0.000000000000 4659.000000000000 -858.145569000000 109.749908000000 0.000000000000 0.000000000000 -11668.033200000000 -858.145569000000 29860.605500000001 42.734611500000 420.251434000000 11668.033200000000 0.000000000000 109.749908000000 42.734611500000 29719.488300000001 2148.823000000000 858.145569000000 -109.749908000000 0.000000000000 420.251434000000 2148.823000000000 629.150513000000 14 19 60 3855.000000000000 0.000000000000 0.000000000000 0.000000000000 9784.138670000000 696.719421000000 0.000000000000 3855.000000000000 0.000000000000 -9784.138670000000 0.000000000000 -99.376640300000 0.000000000000 0.000000000000 3855.000000000000 -696.719421000000 99.376640300000 0.000000000000 0.000000000000 -9784.138670000000 -696.719421000000 25285.831999999999 19.802272800000 376.231628000000 9784.138670000000 0.000000000000 99.376640300000 19.802272800000 25230.607400000001 1772.269900000000 696.719421000000 -99.376640300000 0.000000000000 376.231628000000 1772.269900000000 496.632233000000 14 23 60 2193.000000000000 0.000000000000 0.000000000000 0.000000000000 5943.305660000000 -633.013672000000 0.000000000000 2193.000000000000 0.000000000000 -5943.305660000000 0.000000000000 -785.497375000000 0.000000000000 0.000000000000 2193.000000000000 633.013672000000 785.497375000000 0.000000000000 0.000000000000 -5943.305660000000 633.013672000000 16696.416000000001 414.344269000000 2203.846680000000 5943.305660000000 0.000000000000 785.497375000000 414.344269000000 16625.892599999999 -1817.834110000000 -633.013672000000 -785.497375000000 0.000000000000 2203.846680000000 -1817.834110000000 953.616577000000 14 24 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13133.694299999999 -1744.730710000000 0.000000000000 5000.000000000000 0.000000000000 -13133.694299999999 0.000000000000 -3552.834470000000 0.000000000000 0.000000000000 5000.000000000000 1744.730710000000 3552.834470000000 0.000000000000 0.000000000000 -13133.694299999999 1744.730710000000 36086.835899999998 1128.647710000000 9265.989260000000 13133.694299999999 0.000000000000 3552.834470000000 1128.647710000000 37603.000000000000 -4880.233890000000 -1744.730710000000 -3552.834470000000 0.000000000000 9265.989260000000 -4880.233890000000 4186.014650000000 14 25 60 1279.000000000000 0.000000000000 0.000000000000 0.000000000000 2976.103760000000 30.163513200000 0.000000000000 1279.000000000000 0.000000000000 -2976.103760000000 0.000000000000 -1291.153080000000 0.000000000000 0.000000000000 1279.000000000000 -30.163513200000 1291.153080000000 0.000000000000 0.000000000000 -2976.103760000000 -30.163513200000 7007.464360000000 -28.145660400000 2994.774660000000 2976.103760000000 0.000000000000 1291.153080000000 -28.145660400000 8279.622069999999 81.431182900000 30.163513200000 -1291.153080000000 0.000000000000 2994.774660000000 81.431182900000 1377.532470000000 14 54 60 2516.000000000000 0.000000000000 0.000000000000 0.000000000000 6270.440920000000 533.646545000000 0.000000000000 2516.000000000000 0.000000000000 -6270.440920000000 0.000000000000 -352.080688000000 0.000000000000 0.000000000000 2516.000000000000 -533.646545000000 352.080688000000 0.000000000000 0.000000000000 -6270.440920000000 -533.646545000000 16024.160200000000 -62.015869100000 899.667236000000 6270.440920000000 0.000000000000 352.080688000000 -62.015869100000 16140.062500000000 1360.030150000000 533.646545000000 -352.080688000000 0.000000000000 899.667236000000 1360.030150000000 515.838928000000 14 55 60 4588.000000000000 0.000000000000 0.000000000000 0.000000000000 11286.177700000000 800.654419000000 0.000000000000 4588.000000000000 0.000000000000 -11286.177700000000 0.000000000000 -665.905762000000 0.000000000000 0.000000000000 4588.000000000000 -800.654419000000 665.905762000000 0.000000000000 0.000000000000 -11286.177700000000 -800.654419000000 28499.523399999998 -135.803375000000 1724.870480000000 11286.177700000000 0.000000000000 665.905762000000 -135.803375000000 28791.158200000002 2087.492920000000 800.654419000000 -665.905762000000 0.000000000000 1724.870480000000 2087.492920000000 1004.227780000000 14 56 60 4601.000000000000 0.000000000000 0.000000000000 0.000000000000 11634.071300000000 629.863647000000 0.000000000000 4601.000000000000 0.000000000000 -11634.071300000000 0.000000000000 -1013.970950000000 0.000000000000 0.000000000000 4601.000000000000 -629.863647000000 1013.970950000000 0.000000000000 0.000000000000 -11634.071300000000 -629.863647000000 30045.886699999999 -199.885254000000 2616.150150000000 11634.071300000000 0.000000000000 1013.970950000000 -199.885254000000 30606.000000000000 1722.031860000000 629.863647000000 -1013.970950000000 0.000000000000 2616.150150000000 1722.031860000000 1064.667970000000 14 57 60 4771.000000000000 0.000000000000 0.000000000000 0.000000000000 11814.998000000000 660.690430000000 0.000000000000 4771.000000000000 0.000000000000 -11814.998000000000 0.000000000000 -583.735657000000 0.000000000000 0.000000000000 4771.000000000000 -660.690430000000 583.735657000000 0.000000000000 0.000000000000 -11814.998000000000 -660.690430000000 30007.410199999998 -116.640205000000 1454.592530000000 11814.998000000000 0.000000000000 583.735657000000 -116.640205000000 30347.789100000002 1824.319700000000 660.690430000000 -583.735657000000 0.000000000000 1454.592530000000 1824.319700000000 884.973328000000 14 58 60 2217.000000000000 0.000000000000 0.000000000000 0.000000000000 5378.317380000000 328.970856000000 0.000000000000 2217.000000000000 0.000000000000 -5378.317380000000 0.000000000000 -237.103760000000 0.000000000000 0.000000000000 2217.000000000000 -328.970856000000 237.103760000000 0.000000000000 0.000000000000 -5378.317380000000 -328.970856000000 13424.591800000000 -60.906856500000 577.101685000000 5378.317380000000 0.000000000000 237.103760000000 -60.906856500000 13627.736300000000 880.395752000000 328.970856000000 -237.103760000000 0.000000000000 577.101685000000 880.395752000000 485.631683000000 15 17 60 4561.000000000000 0.000000000000 0.000000000000 0.000000000000 9710.807620000000 2099.931400000000 0.000000000000 4561.000000000000 0.000000000000 -9710.807620000000 0.000000000000 439.326965000000 0.000000000000 0.000000000000 4561.000000000000 -2099.931400000000 -439.326965000000 0.000000000000 0.000000000000 -9710.807620000000 -2099.931400000000 22306.414100000002 246.425140000000 -903.525330000000 9710.807620000000 0.000000000000 -439.326965000000 246.425140000000 21258.148399999998 4690.076660000000 2099.931400000000 439.326965000000 0.000000000000 -903.525330000000 4690.076660000000 1409.630370000000 15 18 60 4701.000000000000 0.000000000000 0.000000000000 0.000000000000 10927.730500000000 2776.431400000000 0.000000000000 4701.000000000000 0.000000000000 -10927.730500000000 0.000000000000 -98.512893700000 0.000000000000 0.000000000000 4701.000000000000 -2776.431400000000 98.512893700000 0.000000000000 0.000000000000 -10927.730500000000 -2776.431400000000 27478.189500000000 -38.532379200000 380.059021000000 10927.730500000000 0.000000000000 98.512893700000 -38.532379200000 25898.252000000000 6492.521000000000 2776.431400000000 -98.512893700000 0.000000000000 380.059021000000 6492.521000000000 2081.613040000000 15 19 60 4188.000000000000 0.000000000000 0.000000000000 0.000000000000 9866.159180000001 2546.823000000000 0.000000000000 4188.000000000000 0.000000000000 -9866.159180000001 0.000000000000 -178.719025000000 0.000000000000 0.000000000000 4188.000000000000 -2546.823000000000 178.719025000000 0.000000000000 0.000000000000 -9866.159180000001 -2546.823000000000 25124.833999999999 -91.343383800000 551.495911000000 9866.159180000001 0.000000000000 178.719025000000 -91.343383800000 23656.140599999999 6013.923340000000 2546.823000000000 -178.719025000000 0.000000000000 551.495911000000 6013.923340000000 1929.433590000000 15 23 60 2524.000000000000 0.000000000000 0.000000000000 0.000000000000 6467.634280000000 839.837402000000 0.000000000000 2524.000000000000 0.000000000000 -6467.634280000000 0.000000000000 -742.384399000000 0.000000000000 0.000000000000 2524.000000000000 -839.837402000000 742.384399000000 0.000000000000 0.000000000000 -6467.634280000000 -839.837402000000 17266.638700000000 -92.889404300000 2022.130980000000 6467.634280000000 0.000000000000 742.384399000000 -92.889404300000 17102.785199999998 2021.918330000000 839.837402000000 -742.384399000000 0.000000000000 2022.130980000000 2021.918330000000 957.703796000000 15 24 60 4888.000000000000 0.000000000000 0.000000000000 0.000000000000 12246.121100000000 1306.021120000000 0.000000000000 4888.000000000000 0.000000000000 -12246.121100000000 0.000000000000 -3207.968510000000 0.000000000000 0.000000000000 4888.000000000000 -1306.021120000000 3207.968510000000 0.000000000000 0.000000000000 -12246.121100000000 -1306.021120000000 31953.718799999999 -950.638428000000 7969.675780000000 12246.121100000000 0.000000000000 3207.968510000000 -950.638428000000 33432.238299999997 2957.252200000000 1306.021120000000 -3207.968510000000 0.000000000000 7969.675780000000 2957.252200000000 3366.634280000000 15 25 60 1487.000000000000 0.000000000000 0.000000000000 0.000000000000 3237.351320000000 741.260132000000 0.000000000000 1487.000000000000 0.000000000000 -3237.351320000000 0.000000000000 -1398.909060000000 0.000000000000 0.000000000000 1487.000000000000 -741.260132000000 1398.909060000000 0.000000000000 0.000000000000 -3237.351320000000 -741.260132000000 7485.872560000000 -688.094360000000 3035.263430000000 3237.351320000000 0.000000000000 1398.909060000000 -688.094360000000 8414.538090000000 1620.880130000000 741.260132000000 -1398.909060000000 0.000000000000 3035.263430000000 1620.880130000000 1760.245360000000 15 54 60 2345.000000000000 0.000000000000 0.000000000000 0.000000000000 5416.899410000000 1603.813480000000 0.000000000000 2345.000000000000 0.000000000000 -5416.899410000000 0.000000000000 -108.501022000000 0.000000000000 0.000000000000 2345.000000000000 -1603.813480000000 108.501022000000 0.000000000000 0.000000000000 -5416.899410000000 -1603.813480000000 13834.318400000000 -89.287948600000 301.058350000000 5416.899410000000 0.000000000000 108.501022000000 -89.287948600000 12887.714800000000 3750.808110000000 1603.813480000000 -108.501022000000 0.000000000000 301.058350000000 3750.808110000000 1424.888430000000 15 55 60 4163.000000000000 0.000000000000 0.000000000000 0.000000000000 9470.768550000001 2637.913330000000 0.000000000000 4163.000000000000 0.000000000000 -9470.768550000001 0.000000000000 -232.575668000000 0.000000000000 0.000000000000 4163.000000000000 -2637.913330000000 232.575668000000 0.000000000000 0.000000000000 -9470.768550000001 -2637.913330000000 23749.041000000001 -226.943695000000 657.835571000000 9470.768550000001 0.000000000000 232.575668000000 -226.943695000000 22370.445299999999 6163.446290000000 2637.913330000000 -232.575668000000 0.000000000000 657.835571000000 6163.446290000000 2416.648440000000 15 56 60 4668.000000000000 0.000000000000 0.000000000000 0.000000000000 10796.436500000000 2908.983150000000 0.000000000000 4668.000000000000 0.000000000000 -10796.436500000000 0.000000000000 -542.890076000000 0.000000000000 0.000000000000 4668.000000000000 -2908.983150000000 542.890076000000 0.000000000000 0.000000000000 -10796.436500000000 -2908.983150000000 27370.839800000002 -415.077728000000 1340.507930000000 10796.436500000000 0.000000000000 542.890076000000 -415.077728000000 25913.958999999999 6930.279790000000 2908.983150000000 -542.890076000000 0.000000000000 1340.507930000000 6930.279790000000 2651.642090000000 15 57 60 4699.000000000000 0.000000000000 0.000000000000 0.000000000000 10670.925800000001 2826.702150000000 0.000000000000 4699.000000000000 0.000000000000 -10670.925800000001 0.000000000000 -145.364227000000 0.000000000000 0.000000000000 4699.000000000000 -2826.702150000000 145.364227000000 0.000000000000 0.000000000000 -10670.925800000001 -2826.702150000000 26592.396499999999 -137.215347000000 397.088531000000 10670.925800000001 0.000000000000 145.364227000000 -137.215347000000 25026.179700000001 6664.538090000000 2826.702150000000 -145.364227000000 0.000000000000 397.088531000000 6664.538090000000 2375.580810000000 15 58 60 2124.000000000000 0.000000000000 0.000000000000 0.000000000000 4739.701660000000 1324.519650000000 0.000000000000 2124.000000000000 0.000000000000 -4739.701660000000 0.000000000000 25.359401700000 0.000000000000 0.000000000000 2124.000000000000 -1324.519650000000 -25.359401700000 0.000000000000 0.000000000000 -4739.701660000000 -1324.519650000000 11733.094700000000 -17.922977400000 -5.477952480000 4739.701660000000 0.000000000000 -25.359401700000 -17.922977400000 10990.552700000000 3065.755860000000 1324.519650000000 25.359401700000 0.000000000000 -5.477952480000 3065.755860000000 1163.595700000000 16 17 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8147.951660000000 1069.200440000000 0.000000000000 5000.000000000000 0.000000000000 -8147.951660000000 0.000000000000 1540.870970000000 0.000000000000 0.000000000000 5000.000000000000 -1069.200440000000 -1540.870970000000 0.000000000000 0.000000000000 -8147.951660000000 -1069.200440000000 14253.709000000001 377.639679000000 -2381.375730000000 8147.951660000000 0.000000000000 -1540.870970000000 377.639679000000 14460.954100000001 1946.013180000000 1069.200440000000 1540.870970000000 0.000000000000 -2381.375730000000 1946.013180000000 1161.696780000000 16 19 60 4615.000000000000 0.000000000000 0.000000000000 0.000000000000 8996.092769999999 1723.838990000000 0.000000000000 4615.000000000000 0.000000000000 -8996.092769999999 0.000000000000 564.032349000000 0.000000000000 0.000000000000 4615.000000000000 -1723.838990000000 -564.032349000000 0.000000000000 0.000000000000 -8996.092769999999 -1723.838990000000 18567.500000000000 214.690048000000 -970.103760000000 8996.092769999999 0.000000000000 -564.032349000000 214.690048000000 18025.650399999999 3402.401120000000 1723.838990000000 564.032349000000 0.000000000000 -970.103760000000 3402.401120000000 1128.781490000000 16 20 60 4996.000000000000 0.000000000000 0.000000000000 0.000000000000 8151.820310000000 1127.116580000000 0.000000000000 4996.000000000000 0.000000000000 -8151.820310000000 0.000000000000 1997.659180000000 0.000000000000 0.000000000000 4996.000000000000 -1127.116580000000 -1997.659180000000 0.000000000000 0.000000000000 -8151.820310000000 -1127.116580000000 14008.650400000000 469.221497000000 -3155.380130000000 8151.820310000000 0.000000000000 -1997.659180000000 469.221497000000 14519.240200000000 1950.760250000000 1127.116580000000 1997.659180000000 0.000000000000 -3155.380130000000 1950.760250000000 1303.292850000000 16 21 60 3206.000000000000 0.000000000000 0.000000000000 0.000000000000 5019.809080000000 397.842316000000 0.000000000000 3206.000000000000 0.000000000000 -5019.809080000000 0.000000000000 1166.094240000000 0.000000000000 0.000000000000 3206.000000000000 -397.842316000000 -1166.094240000000 0.000000000000 0.000000000000 -5019.809080000000 -397.842316000000 8128.474610000000 163.343765000000 -1791.375980000000 5019.809080000000 0.000000000000 -1166.094240000000 163.343765000000 8526.961910000000 675.854187000000 397.842316000000 1166.094240000000 0.000000000000 -1791.375980000000 675.854187000000 603.669128000000 16 22 60 2563.000000000000 0.000000000000 0.000000000000 0.000000000000 4698.739750000000 616.051819000000 0.000000000000 2563.000000000000 0.000000000000 -4698.739750000000 0.000000000000 750.688171000000 0.000000000000 0.000000000000 2563.000000000000 -616.051819000000 -750.688171000000 0.000000000000 0.000000000000 -4698.739750000000 -616.051819000000 8934.754880000000 191.490555000000 -1338.635250000000 4698.739750000000 0.000000000000 -750.688171000000 191.490555000000 9013.021479999999 1176.988160000000 616.051819000000 750.688171000000 0.000000000000 -1338.635250000000 1176.988160000000 482.467224000000 16 23 60 2741.000000000000 0.000000000000 0.000000000000 0.000000000000 5966.214840000000 8.818766590000 0.000000000000 2741.000000000000 0.000000000000 -5966.214840000000 0.000000000000 -611.497803000000 0.000000000000 0.000000000000 2741.000000000000 -8.818766590000 611.497803000000 0.000000000000 0.000000000000 -5966.214840000000 -8.818766590000 13437.877899999999 218.425568000000 1482.062010000000 5966.214840000000 0.000000000000 611.497803000000 218.425568000000 13518.043900000001 -135.215546000000 8.818766590000 -611.497803000000 0.000000000000 1482.062010000000 -135.215546000000 697.744385000000 16 25 60 1294.000000000000 0.000000000000 0.000000000000 0.000000000000 2394.943850000000 292.965302000000 0.000000000000 1294.000000000000 0.000000000000 -2394.943850000000 0.000000000000 -1053.097410000000 0.000000000000 0.000000000000 1294.000000000000 -292.965302000000 1053.097410000000 0.000000000000 0.000000000000 -2394.943850000000 -292.965302000000 4556.756840000000 -228.487946000000 1946.793460000000 2394.943850000000 0.000000000000 1053.097410000000 -228.487946000000 5328.079100000000 558.958496000000 292.965302000000 -1053.097410000000 0.000000000000 1946.793460000000 558.958496000000 992.691284000000 16 54 60 3100.000000000000 0.000000000000 0.000000000000 0.000000000000 5792.349120000000 1260.975100000000 0.000000000000 3100.000000000000 0.000000000000 -5792.349120000000 0.000000000000 330.006561000000 0.000000000000 0.000000000000 3100.000000000000 -1260.975100000000 -330.006561000000 0.000000000000 0.000000000000 -5792.349120000000 -1260.975100000000 11725.898400000000 87.578033400000 -456.826141000000 5792.349120000000 0.000000000000 -330.006561000000 87.578033400000 11414.946300000000 2441.999510000000 1260.975100000000 330.006561000000 0.000000000000 -456.826141000000 2441.999510000000 982.543152000000 16 58 60 3561.000000000000 0.000000000000 0.000000000000 0.000000000000 5997.564940000000 1075.875610000000 0.000000000000 3561.000000000000 0.000000000000 -5997.564940000000 0.000000000000 982.136536000000 0.000000000000 0.000000000000 3561.000000000000 -1075.875610000000 -982.136536000000 0.000000000000 0.000000000000 -5997.564940000000 -1075.875610000000 10948.207000000000 240.428360000000 -1425.113160000000 5997.564940000000 0.000000000000 -982.136536000000 240.428360000000 11053.595700000000 1948.856570000000 1075.875610000000 982.136536000000 0.000000000000 -1425.113160000000 1948.856570000000 1071.187620000000 17 23 60 1448.000000000000 0.000000000000 0.000000000000 0.000000000000 1973.268680000000 162.023132000000 0.000000000000 1448.000000000000 0.000000000000 -1973.268680000000 0.000000000000 -798.932617000000 0.000000000000 0.000000000000 1448.000000000000 -162.023132000000 798.932617000000 0.000000000000 0.000000000000 -1973.268680000000 -162.023132000000 2759.912840000000 -94.692520100000 1089.392090000000 1973.268680000000 0.000000000000 798.932617000000 -94.692520100000 3168.595460000000 240.001938000000 162.023132000000 -798.932617000000 0.000000000000 1089.392090000000 240.001938000000 505.393341000000 17 34 60 904.000000000000 0.000000000000 0.000000000000 0.000000000000 705.499939000000 -138.320663000000 0.000000000000 904.000000000000 0.000000000000 -705.499939000000 0.000000000000 -23.014589300000 0.000000000000 0.000000000000 904.000000000000 138.320663000000 23.014589300000 0.000000000000 0.000000000000 -705.499939000000 138.320663000000 585.269531000000 4.081141470000 17.175041200000 705.499939000000 0.000000000000 23.014589300000 4.081141470000 575.671570000000 -103.853897000000 -138.320663000000 -23.014589300000 0.000000000000 17.175041200000 -103.853897000000 35.519680000000 18 24 60 1255.000000000000 0.000000000000 0.000000000000 0.000000000000 1382.862060000000 -217.674438000000 0.000000000000 1255.000000000000 0.000000000000 -1382.862060000000 0.000000000000 -673.231018000000 0.000000000000 0.000000000000 1255.000000000000 217.674438000000 673.231018000000 0.000000000000 0.000000000000 -1382.862060000000 217.674438000000 1612.394170000000 123.566177000000 763.399414000000 1382.862060000000 0.000000000000 673.231018000000 123.566177000000 1931.915770000000 -247.635590000000 -217.674438000000 -673.231018000000 0.000000000000 763.399414000000 -247.635590000000 443.622345000000 18 59 60 606.000000000000 0.000000000000 0.000000000000 0.000000000000 629.329102000000 5.968397620000 0.000000000000 606.000000000000 0.000000000000 -629.329102000000 0.000000000000 -251.521439000000 0.000000000000 0.000000000000 606.000000000000 -5.968397620000 251.521439000000 0.000000000000 0.000000000000 -629.329102000000 -5.968397620000 681.883606000000 -11.123715400000 267.187500000000 629.329102000000 0.000000000000 251.521439000000 -11.123715400000 779.716553000000 17.266361200000 5.968397620000 -251.521439000000 0.000000000000 267.187500000000 17.266361200000 130.394531000000 19 21 60 2783.000000000000 0.000000000000 0.000000000000 0.000000000000 2182.099120000000 -634.231018000000 0.000000000000 2783.000000000000 0.000000000000 -2182.099120000000 0.000000000000 861.895813000000 0.000000000000 0.000000000000 2783.000000000000 634.231018000000 -861.895813000000 0.000000000000 0.000000000000 -2182.099120000000 634.231018000000 1935.713010000000 -186.115051000000 -669.437744000000 2182.099120000000 0.000000000000 -861.895813000000 -186.115051000000 2037.507570000000 -481.793640000000 -634.231018000000 861.895813000000 0.000000000000 -669.437744000000 -481.793640000000 500.928345000000 19 24 60 1536.000000000000 0.000000000000 0.000000000000 0.000000000000 1316.951660000000 -430.466064000000 0.000000000000 1536.000000000000 0.000000000000 -1316.951660000000 0.000000000000 -516.659790000000 0.000000000000 0.000000000000 1536.000000000000 430.466064000000 516.659790000000 0.000000000000 0.000000000000 -1316.951660000000 430.466064000000 1288.644040000000 153.723328000000 466.998901000000 1316.951660000000 0.000000000000 516.659790000000 153.723328000000 1357.645020000000 -375.804688000000 -430.466064000000 -516.659790000000 0.000000000000 466.998901000000 -375.804688000000 345.035583000000 19 59 60 684.000000000000 0.000000000000 0.000000000000 0.000000000000 541.602478000000 -85.933647200000 0.000000000000 684.000000000000 0.000000000000 -541.602478000000 0.000000000000 -129.064621000000 0.000000000000 0.000000000000 684.000000000000 85.933647200000 129.064621000000 0.000000000000 0.000000000000 -541.602478000000 85.933647200000 467.088898000000 5.388507370000 108.373589000000 541.602478000000 0.000000000000 129.064621000000 5.388507370000 477.121765000000 -58.650550800000 -85.933647200000 -129.064621000000 0.000000000000 108.373589000000 -58.650550800000 65.600807200000 20 23 60 532.000000000000 0.000000000000 0.000000000000 0.000000000000 452.411377000000 -10.057507500000 0.000000000000 532.000000000000 0.000000000000 -452.411377000000 0.000000000000 -198.229294000000 0.000000000000 0.000000000000 532.000000000000 10.057507500000 198.229294000000 0.000000000000 0.000000000000 -452.411377000000 10.057507500000 407.158569000000 -2.533640860000 174.564224000000 452.411377000000 0.000000000000 198.229294000000 -2.533640860000 476.027313000000 -0.109420374000 -10.057507500000 -198.229294000000 0.000000000000 174.564224000000 -0.109420374000 93.719802900000 21 23 60 252.000000000000 0.000000000000 0.000000000000 0.000000000000 195.882446000000 -19.801904700000 0.000000000000 252.000000000000 0.000000000000 -195.882446000000 0.000000000000 -82.251632700000 0.000000000000 0.000000000000 252.000000000000 19.801904700000 82.251632700000 0.000000000000 0.000000000000 -195.882446000000 19.801904700000 158.914276000000 5.180610660000 63.724964100000 195.882446000000 0.000000000000 82.251632700000 5.180610660000 181.275589000000 -14.605344800000 -19.801904700000 -82.251632700000 0.000000000000 63.724964100000 -14.605344800000 33.254436500000 21 34 60 447.000000000000 0.000000000000 0.000000000000 0.000000000000 296.053162000000 -55.411090900000 0.000000000000 447.000000000000 0.000000000000 -296.053162000000 0.000000000000 112.638489000000 0.000000000000 0.000000000000 447.000000000000 55.411090900000 -112.638489000000 0.000000000000 0.000000000000 -296.053162000000 55.411090900000 206.723083000000 -13.395490600000 -75.257057200000 296.053162000000 0.000000000000 -112.638489000000 -13.395490600000 228.104965000000 -34.844429000000 -55.411090900000 112.638489000000 0.000000000000 -75.257057200000 -34.844429000000 38.219955400000 22 59 60 365.000000000000 0.000000000000 0.000000000000 0.000000000000 213.755402000000 -29.918207200000 0.000000000000 365.000000000000 0.000000000000 -213.755402000000 0.000000000000 -142.426926000000 0.000000000000 0.000000000000 365.000000000000 29.918207200000 142.426926000000 0.000000000000 0.000000000000 -213.755402000000 29.918207200000 134.551575000000 8.583219530000 84.308021500000 213.755402000000 0.000000000000 142.426926000000 8.583219530000 187.818436000000 -16.076286300000 -29.918207200000 -142.426926000000 0.000000000000 84.308021500000 -16.076286300000 68.393585200000 23 25 60 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 0.000000000000 23 59 60 519.000000000000 0.000000000000 0.000000000000 0.000000000000 304.416718000000 -12.367395400000 0.000000000000 519.000000000000 0.000000000000 -304.416718000000 0.000000000000 -81.689796400000 0.000000000000 0.000000000000 519.000000000000 12.367395400000 81.689796400000 0.000000000000 0.000000000000 -304.416718000000 12.367395400000 191.745361000000 -5.608261590000 49.197170300000 304.416718000000 0.000000000000 81.689796400000 -5.608261590000 206.673813000000 -4.984163280000 -12.367395400000 -81.689796400000 0.000000000000 49.197170300000 -4.984163280000 37.706405600000 24 26 60 252.000000000000 0.000000000000 0.000000000000 0.000000000000 156.148010000000 24.477855700000 0.000000000000 252.000000000000 0.000000000000 -156.148010000000 0.000000000000 -140.752991000000 0.000000000000 0.000000000000 252.000000000000 -24.477855700000 140.752991000000 0.000000000000 0.000000000000 -156.148010000000 -24.477855700000 104.308533000000 -12.507287000000 88.126564000000 156.148010000000 0.000000000000 140.752991000000 -12.507287000000 179.267456000000 14.181232500000 24.477855700000 -140.752991000000 0.000000000000 88.126564000000 14.181232500000 87.720993000000 24 52 60 399.000000000000 0.000000000000 0.000000000000 0.000000000000 273.995514000000 100.178612000000 0.000000000000 399.000000000000 0.000000000000 -273.995514000000 0.000000000000 -74.447799700000 0.000000000000 0.000000000000 399.000000000000 -100.178612000000 74.447799700000 0.000000000000 0.000000000000 -273.995514000000 -100.178612000000 226.279694000000 -13.541006100000 39.286392200000 273.995514000000 0.000000000000 74.447799700000 -13.541006100000 230.550018000000 72.655921900000 100.178612000000 -74.447799700000 0.000000000000 39.286392200000 72.655921900000 62.223598500000 24 54 60 290.000000000000 0.000000000000 0.000000000000 0.000000000000 194.260132000000 61.488056200000 0.000000000000 290.000000000000 0.000000000000 -194.260132000000 0.000000000000 8.194767950000 0.000000000000 0.000000000000 290.000000000000 -61.488056200000 -8.194767950000 0.000000000000 0.000000000000 -194.260132000000 -61.488056200000 150.023453000000 1.313705920000 -10.793961500000 194.260132000000 0.000000000000 -8.194767950000 1.313705920000 150.190292000000 42.414806400000 61.488056200000 8.194767950000 0.000000000000 -10.793961500000 42.414806400000 34.534114800000 24 55 60 586.000000000000 0.000000000000 0.000000000000 0.000000000000 372.277405000000 90.699935900000 0.000000000000 586.000000000000 0.000000000000 -372.277405000000 0.000000000000 -33.855007200000 0.000000000000 0.000000000000 586.000000000000 -90.699935900000 33.855007200000 0.000000000000 0.000000000000 -372.277405000000 -90.699935900000 268.037872000000 -16.503223400000 12.480788200000 372.277405000000 0.000000000000 33.855007200000 -16.503223400000 286.642365000000 59.152111100000 90.699935900000 -33.855007200000 0.000000000000 12.480788200000 59.152111100000 71.578270000000 24 56 60 797.000000000000 0.000000000000 0.000000000000 0.000000000000 524.162720000000 105.638046000000 0.000000000000 797.000000000000 0.000000000000 -524.162720000000 0.000000000000 -5.922789100000 0.000000000000 0.000000000000 797.000000000000 -105.638046000000 5.922789100000 0.000000000000 0.000000000000 -524.162720000000 -105.638046000000 381.463562000000 -12.346553800000 -8.329345700000 524.162720000000 0.000000000000 5.922789100000 -12.346553800000 407.668671000000 71.477020300000 105.638046000000 -5.922789100000 0.000000000000 -8.329345700000 71.477020300000 81.527603100000 24 57 60 437.000000000000 0.000000000000 0.000000000000 0.000000000000 270.458435000000 56.538909900000 0.000000000000 437.000000000000 0.000000000000 -270.458435000000 0.000000000000 -8.111837390000 0.000000000000 0.000000000000 437.000000000000 -56.538909900000 8.111837390000 0.000000000000 0.000000000000 -270.458435000000 -56.538909900000 182.997269000000 -6.243640900000 -1.425425170000 270.458435000000 0.000000000000 8.111837390000 -6.243640900000 200.238174000000 35.627498600000 56.538909900000 -8.111837390000 0.000000000000 -1.425425170000 35.627498600000 42.818916300000 25 27 60 278.000000000000 0.000000000000 0.000000000000 0.000000000000 199.505722000000 -4.530136590000 0.000000000000 278.000000000000 0.000000000000 -199.505722000000 0.000000000000 -123.107887000000 0.000000000000 0.000000000000 278.000000000000 4.530136590000 123.107887000000 0.000000000000 0.000000000000 -199.505722000000 4.530136590000 173.754456000000 -4.012110710000 109.500534000000 199.505722000000 0.000000000000 123.107887000000 -4.012110710000 246.804794000000 0.440537721000 -4.530136590000 -123.107887000000 0.000000000000 109.500534000000 0.440537721000 86.677825900000 25 52 60 1012.000000000000 0.000000000000 0.000000000000 0.000000000000 868.900757000000 90.479576100000 0.000000000000 1012.000000000000 0.000000000000 -868.900757000000 0.000000000000 -468.510437000000 0.000000000000 0.000000000000 1012.000000000000 -90.479576100000 468.510437000000 0.000000000000 0.000000000000 -868.900757000000 -90.479576100000 776.241211000000 -65.069129900000 422.208160000000 868.900757000000 0.000000000000 468.510437000000 -65.069129900000 1119.933230000000 81.387672400000 90.479576100000 -468.510437000000 0.000000000000 422.208160000000 81.387672400000 379.433472000000 25 54 60 262.000000000000 0.000000000000 0.000000000000 0.000000000000 170.858093000000 -3.630888220000 0.000000000000 262.000000000000 0.000000000000 -170.858093000000 0.000000000000 -23.111038200000 0.000000000000 0.000000000000 262.000000000000 3.630888220000 23.111038200000 0.000000000000 0.000000000000 -170.858093000000 3.630888220000 114.049545000000 1.603593950000 12.377038000000 170.858093000000 0.000000000000 23.111038200000 1.603593950000 128.654297000000 -1.497774480000 -3.630888220000 -23.111038200000 0.000000000000 12.377038000000 -1.497774480000 16.937109000000 25 55 60 326.000000000000 0.000000000000 0.000000000000 0.000000000000 220.167923000000 2.993263010000 0.000000000000 326.000000000000 0.000000000000 -220.167923000000 0.000000000000 -26.327648200000 0.000000000000 0.000000000000 326.000000000000 -2.993263010000 26.327648200000 0.000000000000 0.000000000000 -220.167923000000 -2.993263010000 152.697449000000 -0.494876266000 15.290187800000 220.167923000000 0.000000000000 26.327648200000 -0.494876266000 172.147858000000 3.052313800000 2.993263010000 -26.327648200000 0.000000000000 15.290187800000 3.052313800000 23.525684400000 25 56 60 397.000000000000 0.000000000000 0.000000000000 0.000000000000 280.222534000000 11.693690300000 0.000000000000 397.000000000000 0.000000000000 -280.222534000000 0.000000000000 -37.188858000000 0.000000000000 0.000000000000 397.000000000000 -11.693690300000 37.188858000000 0.000000000000 0.000000000000 -280.222534000000 -11.693690300000 205.223282000000 -4.012911800000 25.133224500000 280.222534000000 0.000000000000 37.188858000000 -4.012911800000 234.957779000000 10.409548800000 11.693690300000 -37.188858000000 0.000000000000 25.133224500000 10.409548800000 37.682869000000 25 57 60 375.000000000000 0.000000000000 0.000000000000 0.000000000000 244.825241000000 0.137610435000 0.000000000000 375.000000000000 0.000000000000 -244.825241000000 0.000000000000 -45.913246200000 0.000000000000 0.000000000000 375.000000000000 -0.137610435000 45.913246200000 0.000000000000 0.000000000000 -244.825241000000 -0.137610435000 164.490540000000 -2.950865750000 27.399673500000 244.825241000000 0.000000000000 45.913246200000 -2.950865750000 193.761353000000 1.005311850000 0.137610435000 -45.913246200000 0.000000000000 27.399673500000 1.005311850000 35.023185700000 25 58 60 222.000000000000 0.000000000000 0.000000000000 0.000000000000 143.453278000000 8.238599780000 0.000000000000 222.000000000000 0.000000000000 -143.453278000000 0.000000000000 -63.549030300000 0.000000000000 0.000000000000 222.000000000000 -8.238599780000 63.549030300000 0.000000000000 0.000000000000 -143.453278000000 -8.238599780000 97.311485300000 -5.553084370000 42.077602400000 143.453278000000 0.000000000000 63.549030300000 -5.553084370000 128.650574000000 6.675376890000 8.238599780000 -63.549030300000 0.000000000000 42.077602400000 6.675376890000 37.274707800000 25 59 60 492.000000000000 0.000000000000 0.000000000000 0.000000000000 387.031616000000 49.055992100000 0.000000000000 492.000000000000 0.000000000000 -387.031616000000 0.000000000000 -249.028122000000 0.000000000000 0.000000000000 492.000000000000 -49.055992100000 249.028122000000 0.000000000000 0.000000000000 -387.031616000000 -49.055992100000 324.808716000000 -36.072135900000 209.657593000000 387.031616000000 0.000000000000 249.028122000000 -36.072135900000 488.014709000000 44.318119000000 49.055992100000 -249.028122000000 0.000000000000 209.657593000000 44.318119000000 185.468109000000 26 42 60 2103.000000000000 0.000000000000 0.000000000000 0.000000000000 5036.740720000000 690.757324000000 0.000000000000 2103.000000000000 0.000000000000 -5036.740720000000 0.000000000000 -2517.320310000000 0.000000000000 0.000000000000 2103.000000000000 -690.757324000000 2517.320310000000 0.000000000000 0.000000000000 -5036.740720000000 -690.757324000000 12388.357400000001 -849.971252000000 6045.884770000000 5036.740720000000 0.000000000000 2517.320310000000 -849.971252000000 15197.334000000001 1656.924440000000 690.757324000000 -2517.320310000000 0.000000000000 6045.884770000000 1656.924440000000 3376.579590000000 26 43 60 2040.000000000000 0.000000000000 0.000000000000 0.000000000000 4763.757810000000 638.809814000000 0.000000000000 2040.000000000000 0.000000000000 -4763.757810000000 0.000000000000 -2361.670170000000 0.000000000000 0.000000000000 2040.000000000000 -638.809814000000 2361.670170000000 0.000000000000 0.000000000000 -4763.757810000000 -638.809814000000 11402.075199999999 -728.381104000000 5548.605470000000 4763.757810000000 0.000000000000 2361.670170000000 -728.381104000000 13974.699199999999 1476.244510000000 638.809814000000 -2361.670170000000 0.000000000000 5548.605470000000 1476.244510000000 3057.762700000000 26 59 60 989.000000000000 0.000000000000 0.000000000000 0.000000000000 1389.556880000000 206.229782000000 0.000000000000 989.000000000000 0.000000000000 -1389.556880000000 0.000000000000 -315.476593000000 0.000000000000 0.000000000000 989.000000000000 -206.229782000000 315.476593000000 0.000000000000 0.000000000000 -1389.556880000000 -206.229782000000 2362.803220000000 -64.236343400000 613.560852000000 1389.556880000000 0.000000000000 315.476593000000 -64.236343400000 2501.565920000000 286.909973000000 206.229782000000 -315.476593000000 0.000000000000 613.560852000000 286.909973000000 282.963531000000 27 29 60 1245.000000000000 0.000000000000 0.000000000000 0.000000000000 3885.535160000000 231.542862000000 0.000000000000 1245.000000000000 0.000000000000 -3885.535160000000 0.000000000000 -1277.424800000000 0.000000000000 0.000000000000 1245.000000000000 -231.542862000000 1277.424800000000 0.000000000000 0.000000000000 -3885.535160000000 -231.542862000000 12350.446300000000 -172.247421000000 4083.775630000000 3885.535160000000 0.000000000000 1277.424800000000 -172.247421000000 13672.091800000000 668.702393000000 231.542862000000 -1277.424800000000 0.000000000000 4083.775630000000 668.702393000000 1541.926030000000 27 42 60 3451.000000000000 0.000000000000 0.000000000000 0.000000000000 9283.465819999999 1446.999150000000 0.000000000000 3451.000000000000 0.000000000000 -9283.465819999999 0.000000000000 -1576.228760000000 0.000000000000 0.000000000000 3451.000000000000 -1446.999150000000 1576.228760000000 0.000000000000 0.000000000000 -9283.465819999999 -1446.999150000000 25963.722699999998 -564.788635000000 4455.117190000000 9283.465819999999 0.000000000000 1576.228760000000 -564.788635000000 26480.638700000000 3885.331790000000 1446.999150000000 -1576.228760000000 0.000000000000 4455.117190000000 3885.331790000000 2118.788570000000 27 43 60 2661.000000000000 0.000000000000 0.000000000000 0.000000000000 7216.336910000000 673.402954000000 0.000000000000 2661.000000000000 0.000000000000 -7216.336910000000 0.000000000000 -1804.498660000000 0.000000000000 0.000000000000 2661.000000000000 -673.402954000000 1804.498660000000 0.000000000000 0.000000000000 -7216.336910000000 -673.402954000000 20102.333999999999 -247.859772000000 5159.355960000000 7216.336910000000 0.000000000000 1804.498660000000 -247.859772000000 21458.906299999999 1708.482790000000 673.402954000000 -1804.498660000000 0.000000000000 5159.355960000000 1708.482790000000 2050.908450000000 27 59 60 1439.000000000000 0.000000000000 0.000000000000 0.000000000000 3676.474850000000 610.656128000000 0.000000000000 1439.000000000000 0.000000000000 -3676.474850000000 0.000000000000 221.636581000000 0.000000000000 0.000000000000 1439.000000000000 -610.656128000000 -221.636581000000 0.000000000000 0.000000000000 -3676.474850000000 -610.656128000000 10141.687500000000 106.499374000000 -568.593079000000 3676.474850000000 0.000000000000 -221.636581000000 106.499374000000 9841.122069999999 1597.937500000000 610.656128000000 221.636581000000 0.000000000000 -568.593079000000 1597.937500000000 412.270172000000 28 42 60 4087.000000000000 0.000000000000 0.000000000000 0.000000000000 11829.946300000000 667.420288000000 0.000000000000 4087.000000000000 0.000000000000 -11829.946300000000 0.000000000000 856.388184000000 0.000000000000 0.000000000000 4087.000000000000 -667.420288000000 -856.388184000000 0.000000000000 0.000000000000 -11829.946300000000 -667.420288000000 34767.105499999998 29.524635300000 -2232.081050000000 11829.946300000000 0.000000000000 -856.388184000000 29.524635300000 35223.042999999998 2014.200560000000 667.420288000000 856.388184000000 0.000000000000 -2232.081050000000 2014.200560000000 969.078979000000 28 43 60 2271.000000000000 0.000000000000 0.000000000000 0.000000000000 6446.009770000000 234.856155000000 0.000000000000 2271.000000000000 0.000000000000 -6446.009770000000 0.000000000000 304.937897000000 0.000000000000 0.000000000000 2271.000000000000 -234.856155000000 -304.937897000000 0.000000000000 0.000000000000 -6446.009770000000 -234.856155000000 18453.744100000000 15.320730200000 -793.203735000000 6446.009770000000 0.000000000000 -304.937897000000 15.320730200000 18526.509800000000 681.377625000000 234.856155000000 304.937897000000 0.000000000000 -793.203735000000 681.377625000000 193.725586000000 28 44 60 1545.000000000000 0.000000000000 0.000000000000 0.000000000000 4761.320800000000 345.186859000000 0.000000000000 1545.000000000000 0.000000000000 -4761.320800000000 0.000000000000 60.099472000000 0.000000000000 0.000000000000 1545.000000000000 -345.186859000000 -60.099472000000 0.000000000000 0.000000000000 -4761.320800000000 -345.186859000000 14802.867200000001 13.893982900000 -170.035217000000 4761.320800000000 0.000000000000 -60.099472000000 13.893982900000 14775.729499999999 1077.578000000000 345.186859000000 60.099472000000 0.000000000000 -170.035217000000 1077.578000000000 137.044601000000 28 59 60 1688.000000000000 0.000000000000 0.000000000000 0.000000000000 3912.525630000000 178.101852000000 0.000000000000 1688.000000000000 0.000000000000 -3912.525630000000 0.000000000000 1306.880490000000 0.000000000000 0.000000000000 1688.000000000000 -178.101852000000 -1306.880490000000 0.000000000000 0.000000000000 -3912.525630000000 -178.101852000000 9927.852540000000 142.624832000000 -3173.837890000000 3912.525630000000 0.000000000000 -1306.880490000000 142.624832000000 10869.121100000000 422.818451000000 178.101852000000 1306.880490000000 0.000000000000 -3173.837890000000 422.818451000000 1166.920780000000 29 39 60 168.000000000000 0.000000000000 0.000000000000 0.000000000000 556.812134000000 -150.629120000000 0.000000000000 168.000000000000 0.000000000000 -556.812134000000 0.000000000000 33.920665700000 0.000000000000 0.000000000000 168.000000000000 150.629120000000 -33.920665700000 0.000000000000 0.000000000000 -556.812134000000 150.629120000000 1983.468870000000 -30.288202300000 -112.591278000000 556.812134000000 0.000000000000 -33.920665700000 -30.288202300000 1855.639280000000 -498.781860000000 -150.629120000000 33.920665700000 0.000000000000 -112.591278000000 -498.781860000000 142.476517000000 29 44 60 640.000000000000 0.000000000000 0.000000000000 0.000000000000 1671.194820000000 -63.442596400000 0.000000000000 640.000000000000 0.000000000000 -1671.194820000000 0.000000000000 676.313538000000 0.000000000000 0.000000000000 640.000000000000 63.442596400000 -676.313538000000 0.000000000000 0.000000000000 -1671.194820000000 63.442596400000 4385.688960000000 -66.736908000000 -1762.708130000000 1671.194820000000 0.000000000000 -676.313538000000 -66.736908000000 5096.629880000000 -163.769287000000 -63.442596400000 676.313538000000 0.000000000000 -1762.708130000000 -163.769287000000 724.834106000000 29 51 60 632.000000000000 0.000000000000 0.000000000000 0.000000000000 1640.251950000000 -383.311188000000 0.000000000000 632.000000000000 0.000000000000 -1640.251950000000 0.000000000000 456.089661000000 0.000000000000 0.000000000000 632.000000000000 383.311188000000 -456.089661000000 0.000000000000 0.000000000000 -1640.251950000000 383.311188000000 4602.736330000000 -192.545273000000 -1189.131230000000 1640.251950000000 0.000000000000 -456.089661000000 -192.545273000000 4677.241700000000 -990.896912000000 -383.311188000000 456.089661000000 0.000000000000 -1189.131230000000 -990.896912000000 749.867676000000 30 31 60 897.000000000000 0.000000000000 0.000000000000 0.000000000000 657.489319000000 -59.585445400000 0.000000000000 897.000000000000 0.000000000000 -657.489319000000 0.000000000000 -542.046387000000 0.000000000000 0.000000000000 897.000000000000 59.585445400000 542.046387000000 0.000000000000 0.000000000000 -657.489319000000 59.585445400000 542.760132000000 25.486547500000 427.438171000000 657.489319000000 0.000000000000 542.046387000000 25.486547500000 882.205200000000 -38.186554000000 -59.585445400000 -542.046387000000 0.000000000000 427.438171000000 -38.186554000000 406.129578000000 30 38 60 2166.000000000000 0.000000000000 0.000000000000 0.000000000000 6874.537600000000 -731.274170000000 0.000000000000 2166.000000000000 0.000000000000 -6874.537600000000 0.000000000000 1996.859990000000 0.000000000000 0.000000000000 2166.000000000000 731.274170000000 -1996.859990000000 0.000000000000 0.000000000000 -6874.537600000000 731.274170000000 22229.968799999999 -631.348083000000 -6369.749510000000 6874.537600000000 0.000000000000 -1996.859990000000 -631.348083000000 23794.677700000000 -2255.638670000000 -731.274170000000 1996.859990000000 0.000000000000 -6369.749510000000 -2255.638670000000 2203.692380000000 30 39 60 2354.000000000000 0.000000000000 0.000000000000 0.000000000000 6934.088870000000 -972.970581000000 0.000000000000 2354.000000000000 0.000000000000 -6934.088870000000 0.000000000000 2381.616460000000 0.000000000000 0.000000000000 2354.000000000000 972.970581000000 -2381.616460000000 0.000000000000 0.000000000000 -6934.088870000000 972.970581000000 21057.111300000000 -933.310547000000 -7026.660160000000 6934.088870000000 0.000000000000 -2381.616460000000 -933.310547000000 23062.757799999999 -2788.995610000000 -972.970581000000 2381.616460000000 0.000000000000 -7026.660160000000 -2788.995610000000 2980.532470000000 30 40 60 2447.000000000000 0.000000000000 0.000000000000 0.000000000000 7167.314450000000 -995.984924000000 0.000000000000 2447.000000000000 0.000000000000 -7167.314450000000 0.000000000000 2483.121340000000 0.000000000000 0.000000000000 2447.000000000000 995.984924000000 -2483.121340000000 0.000000000000 0.000000000000 -7167.314450000000 995.984924000000 21663.697300000000 -957.563293000000 -7293.657710000000 7167.314450000000 0.000000000000 -2483.121340000000 -957.563293000000 23747.222699999998 -2816.629880000000 -995.984924000000 2483.121340000000 0.000000000000 -7293.657710000000 -2816.629880000000 3108.601810000000 30 41 60 1923.000000000000 0.000000000000 0.000000000000 0.000000000000 5690.414060000000 -753.768616000000 0.000000000000 1923.000000000000 0.000000000000 -5690.414060000000 0.000000000000 1997.706180000000 0.000000000000 0.000000000000 1923.000000000000 753.768616000000 -1997.706180000000 0.000000000000 0.000000000000 -5690.414060000000 753.768616000000 17339.183600000000 -736.045532000000 -5913.108890000000 5690.414060000000 0.000000000000 -1997.706180000000 -736.045532000000 19117.818400000000 -2159.478270000000 -753.768616000000 1997.706180000000 0.000000000000 -5913.108890000000 -2159.478270000000 2531.790280000000 30 42 60 2507.000000000000 0.000000000000 0.000000000000 0.000000000000 7300.246580000000 -1053.729490000000 0.000000000000 2507.000000000000 0.000000000000 -7300.246580000000 0.000000000000 2564.706790000000 0.000000000000 0.000000000000 2507.000000000000 1053.729490000000 -2564.706790000000 0.000000000000 0.000000000000 -7300.246580000000 1053.729490000000 21921.986300000000 -1029.514770000000 -7486.115230000000 7300.246580000000 0.000000000000 -2564.706790000000 -1029.514770000000 24086.669900000001 -2993.375240000000 -1053.729490000000 2564.706790000000 0.000000000000 -7486.115230000000 -2993.375240000000 3236.423340000000 30 43 60 1482.000000000000 0.000000000000 0.000000000000 0.000000000000 4388.954100000000 -502.244110000000 0.000000000000 1482.000000000000 0.000000000000 -4388.954100000000 0.000000000000 1655.954470000000 0.000000000000 0.000000000000 1482.000000000000 502.244110000000 -1655.954470000000 0.000000000000 0.000000000000 -4388.954100000000 502.244110000000 13290.133800000000 -533.693726000000 -4917.468750000000 4388.954100000000 0.000000000000 -1655.954470000000 -533.693726000000 14960.479499999999 -1438.554320000000 -502.244110000000 1655.954470000000 0.000000000000 -4917.468750000000 -1438.554320000000 2113.832520000000 30 45 60 2281.000000000000 0.000000000000 0.000000000000 0.000000000000 6582.540040000000 -1045.169190000000 0.000000000000 2281.000000000000 0.000000000000 -6582.540040000000 0.000000000000 2356.879640000000 0.000000000000 0.000000000000 2281.000000000000 1045.169190000000 -2356.879640000000 0.000000000000 0.000000000000 -6582.540040000000 1045.169190000000 19714.320299999999 -1033.067630000000 -6791.633300000000 6582.540040000000 0.000000000000 -2356.879640000000 -1033.067630000000 21673.724600000001 -2939.993900000000 -1045.169190000000 2356.879640000000 0.000000000000 -6791.633300000000 -2939.993900000000 3096.562740000000 30 46 60 2229.000000000000 0.000000000000 0.000000000000 0.000000000000 6630.152340000000 -853.826355000000 0.000000000000 2229.000000000000 0.000000000000 -6630.152340000000 0.000000000000 2291.868900000000 0.000000000000 0.000000000000 2229.000000000000 853.826355000000 -2291.868900000000 0.000000000000 0.000000000000 -6630.152340000000 853.826355000000 20299.541000000001 -824.437439000000 -6831.557130000000 6630.152340000000 0.000000000000 -2291.868900000000 -824.437439000000 22311.958999999999 -2449.806880000000 -853.826355000000 2291.868900000000 0.000000000000 -6831.557130000000 -2449.806880000000 2862.821040000000 30 47 60 2101.000000000000 0.000000000000 0.000000000000 0.000000000000 6170.400880000000 -862.980652000000 0.000000000000 2101.000000000000 0.000000000000 -6170.400880000000 0.000000000000 2170.853030000000 0.000000000000 0.000000000000 2101.000000000000 862.980652000000 -2170.853030000000 0.000000000000 0.000000000000 -6170.400880000000 862.980652000000 18693.984400000001 -846.887878000000 -6374.704100000000 6170.400880000000 0.000000000000 -2170.853030000000 -846.887878000000 20578.580099999999 -2458.667720000000 -862.980652000000 2170.853030000000 0.000000000000 -6374.704100000000 -2458.667720000000 2762.208250000000 30 48 60 1367.000000000000 0.000000000000 0.000000000000 0.000000000000 3839.878420000000 -727.320435000000 0.000000000000 1367.000000000000 0.000000000000 -3839.878420000000 0.000000000000 1274.538450000000 0.000000000000 0.000000000000 1367.000000000000 727.320435000000 -1274.538450000000 0.000000000000 0.000000000000 -3839.878420000000 727.320435000000 11259.702100000000 -678.568298000000 -3547.632080000000 3839.878420000000 0.000000000000 -1274.538450000000 -678.568298000000 12078.483399999999 -2027.693480000000 -727.320435000000 1274.538450000000 0.000000000000 -3547.632080000000 -2027.693480000000 1634.729130000000 30 49 60 2252.000000000000 0.000000000000 0.000000000000 0.000000000000 6551.183590000000 -1048.797970000000 0.000000000000 2252.000000000000 0.000000000000 -6551.183590000000 0.000000000000 2195.881100000000 0.000000000000 0.000000000000 2252.000000000000 1048.797970000000 -2195.881100000000 0.000000000000 0.000000000000 -6551.183590000000 1048.797970000000 19767.878900000000 -1022.226560000000 -6348.959470000000 6551.183590000000 0.000000000000 -2195.881100000000 -1022.226560000000 21417.164100000002 -2987.582030000000 -1048.797970000000 2195.881100000000 0.000000000000 -6348.959470000000 -2987.582030000000 2773.317630000000 30 50 60 1737.000000000000 0.000000000000 0.000000000000 0.000000000000 4743.212890000000 -1063.507930000000 0.000000000000 1737.000000000000 0.000000000000 -4743.212890000000 0.000000000000 1756.624390000000 0.000000000000 0.000000000000 1737.000000000000 1063.507930000000 -1756.624390000000 0.000000000000 0.000000000000 -4743.212890000000 1063.507930000000 13729.863300000001 -1058.995480000000 -4804.514160000000 4743.212890000000 0.000000000000 -1756.624390000000 -1058.995480000000 14820.492200000001 -2868.456050000000 -1063.507930000000 1756.624390000000 0.000000000000 -4804.514160000000 -2868.456050000000 2581.105220000000 31 33 60 615.000000000000 0.000000000000 0.000000000000 0.000000000000 1363.061890000000 -529.724365000000 0.000000000000 615.000000000000 0.000000000000 -1363.061890000000 0.000000000000 -873.374023000000 0.000000000000 0.000000000000 615.000000000000 529.724365000000 873.374023000000 0.000000000000 0.000000000000 -1363.061890000000 529.724365000000 3526.000980000000 744.979126000000 1934.600710000000 1363.061890000000 0.000000000000 873.374023000000 744.979126000000 4265.472660000000 -1172.181880000000 -529.724365000000 -873.374023000000 0.000000000000 1934.600710000000 -1172.181880000000 1747.211060000000 31 35 60 2711.000000000000 0.000000000000 0.000000000000 0.000000000000 6213.397950000000 -2392.732670000000 0.000000000000 2711.000000000000 0.000000000000 -6213.397950000000 0.000000000000 -3578.959960000000 0.000000000000 0.000000000000 2711.000000000000 2392.732670000000 3578.959960000000 0.000000000000 0.000000000000 -6213.397950000000 2392.732670000000 16479.375000000000 3125.812990000000 8183.493160000000 6213.397950000000 0.000000000000 3578.959960000000 3125.812990000000 19014.066400000000 -5489.894530000000 -2392.732670000000 -3578.959960000000 0.000000000000 8183.493160000000 -5489.894530000000 6989.296880000000 31 36 60 3133.000000000000 0.000000000000 0.000000000000 0.000000000000 7199.706540000000 -2579.117680000000 0.000000000000 3133.000000000000 0.000000000000 -7199.706540000000 0.000000000000 -4146.035640000000 0.000000000000 0.000000000000 3133.000000000000 2579.117680000000 4146.035640000000 0.000000000000 0.000000000000 -7199.706540000000 2579.117680000000 18845.615200000000 3383.536380000000 9508.257809999999 7199.706540000000 0.000000000000 4146.035640000000 3383.536380000000 22080.205099999999 -5924.877930000000 -2579.117680000000 -4146.035640000000 0.000000000000 9508.257809999999 -5924.877930000000 7809.125980000000 31 37 60 2039.000000000000 0.000000000000 0.000000000000 0.000000000000 4662.305180000000 -1987.054200000000 0.000000000000 2039.000000000000 0.000000000000 -4662.305180000000 0.000000000000 -2652.241460000000 0.000000000000 0.000000000000 2039.000000000000 1987.054200000000 2652.241460000000 0.000000000000 0.000000000000 -4662.305180000000 1987.054200000000 12641.289100000000 2581.229000000000 6047.758790000000 4662.305180000000 0.000000000000 2652.241460000000 2581.229000000000 14147.623000000000 -4542.155270000000 -1987.054200000000 -2652.241460000000 0.000000000000 6047.758790000000 -4542.155270000000 5444.731450000000 32 37 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14173.397499999999 -4032.603520000000 0.000000000000 5000.000000000000 0.000000000000 -14173.397499999999 0.000000000000 -1359.216310000000 0.000000000000 0.000000000000 5000.000000000000 4032.603520000000 1359.216310000000 0.000000000000 0.000000000000 -14173.397499999999 4032.603520000000 43971.417999999998 1225.611820000000 3829.323240000000 14173.397499999999 0.000000000000 1359.216310000000 1225.611820000000 40780.503900000003 -11443.040999999999 -4032.603520000000 -1359.216310000000 0.000000000000 3829.323240000000 -11443.040999999999 4388.441410000000 33 37 60 3081.000000000000 0.000000000000 0.000000000000 0.000000000000 7955.550780000000 -1692.449460000000 0.000000000000 3081.000000000000 0.000000000000 -7955.550780000000 0.000000000000 3152.619140000000 0.000000000000 0.000000000000 3081.000000000000 1692.449460000000 -3152.619140000000 0.000000000000 0.000000000000 -7955.550780000000 1692.449460000000 21807.296900000001 -1703.342770000000 -8110.714840000000 7955.550780000000 0.000000000000 -3152.619140000000 -1703.342770000000 23853.628900000000 -4426.964360000000 -1692.449460000000 3152.619140000000 0.000000000000 -8110.714840000000 -4426.964360000000 4533.291500000000 34 36 60 417.000000000000 0.000000000000 0.000000000000 0.000000000000 994.020752000000 -30.769109700000 0.000000000000 417.000000000000 0.000000000000 -994.020752000000 0.000000000000 550.903625000000 0.000000000000 0.000000000000 417.000000000000 30.769109700000 -550.903625000000 0.000000000000 0.000000000000 -994.020752000000 30.769109700000 2408.122070000000 -39.516235400000 -1317.961430000000 994.020752000000 0.000000000000 -550.903625000000 -39.516235400000 3115.601810000000 -78.057342500000 -30.769109700000 550.903625000000 0.000000000000 -1317.961430000000 -78.057342500000 756.702942000000 34 58 60 581.000000000000 0.000000000000 0.000000000000 0.000000000000 464.149841000000 -19.037771200000 0.000000000000 581.000000000000 0.000000000000 -464.149841000000 0.000000000000 -165.595215000000 0.000000000000 0.000000000000 581.000000000000 19.037771200000 165.595215000000 0.000000000000 0.000000000000 -464.149841000000 19.037771200000 396.549713000000 1.266047600000 137.573120000000 464.149841000000 0.000000000000 165.595215000000 1.266047600000 441.150085000000 -4.111905100000 -19.037771200000 -165.595215000000 0.000000000000 137.573120000000 -4.111905100000 65.766548200000 37 39 60 1575.000000000000 0.000000000000 0.000000000000 0.000000000000 2845.706300000000 530.557312000000 0.000000000000 1575.000000000000 0.000000000000 -2845.706300000000 0.000000000000 2143.666990000000 0.000000000000 0.000000000000 1575.000000000000 -530.557312000000 -2143.666990000000 0.000000000000 0.000000000000 -2845.706300000000 -530.557312000000 5405.711430000000 717.084839000000 -3875.370120000000 2845.706300000000 0.000000000000 -2143.666990000000 717.084839000000 8117.864750000000 965.229004000000 530.557312000000 2143.666990000000 0.000000000000 -3875.370120000000 965.229004000000 3149.420410000000 37 40 60 1905.000000000000 0.000000000000 0.000000000000 0.000000000000 3372.047360000000 588.547974000000 0.000000000000 1905.000000000000 0.000000000000 -3372.047360000000 0.000000000000 2594.473880000000 0.000000000000 0.000000000000 1905.000000000000 -588.547974000000 -2594.473880000000 0.000000000000 0.000000000000 -3372.047360000000 -588.547974000000 6271.522460000000 792.275757000000 -4597.797360000000 3372.047360000000 0.000000000000 -2594.473880000000 792.275757000000 9579.473630000000 1040.470460000000 588.547974000000 2594.473880000000 0.000000000000 -4597.797360000000 1040.470460000000 3790.073970000000 37 46 60 1377.000000000000 0.000000000000 0.000000000000 0.000000000000 2407.764160000000 529.366394000000 0.000000000000 1377.000000000000 0.000000000000 -2407.764160000000 0.000000000000 1831.377200000000 0.000000000000 0.000000000000 1377.000000000000 -529.366394000000 -1831.377200000000 0.000000000000 0.000000000000 -2407.764160000000 -529.366394000000 4492.422850000000 690.902710000000 -3208.052490000000 2407.764160000000 0.000000000000 -1831.377200000000 690.902710000000 6701.194340000000 931.177673000000 529.366394000000 1831.377200000000 0.000000000000 -3208.052490000000 931.177673000000 2711.755370000000 38 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13438.540000000001 4176.386230000000 0.000000000000 5000.000000000000 0.000000000000 -13438.540000000001 0.000000000000 3383.547850000000 0.000000000000 0.000000000000 5000.000000000000 -4176.386230000000 -3383.547850000000 0.000000000000 0.000000000000 -13438.540000000001 -4176.386230000000 40618.792999999998 2662.480220000000 -8922.835940000001 13438.540000000001 0.000000000000 -3383.547850000000 2662.480220000000 39250.128900000003 11611.828100000001 4176.386230000000 3383.547850000000 0.000000000000 -8922.835940000001 11611.828100000001 6879.426760000000 38 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11375.727500000001 1464.499880000000 0.000000000000 5000.000000000000 0.000000000000 -11375.727500000001 0.000000000000 4554.756840000000 0.000000000000 0.000000000000 5000.000000000000 -1464.499880000000 -4554.756840000000 0.000000000000 0.000000000000 -11375.727500000001 -1464.499880000000 27301.009800000000 1474.233400000000 -10360.373000000000 11375.727500000001 0.000000000000 -4554.756840000000 1474.233400000000 30871.230500000001 3543.740480000000 1464.499880000000 4554.756840000000 0.000000000000 -10360.373000000000 3543.740480000000 5159.642580000000 38 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12150.489299999999 2793.996340000000 0.000000000000 5000.000000000000 0.000000000000 -12150.489299999999 0.000000000000 4646.631840000000 0.000000000000 0.000000000000 5000.000000000000 -2793.996340000000 -4646.631840000000 0.000000000000 0.000000000000 -12150.489299999999 -2793.996340000000 32174.081999999999 2941.075680000000 -11430.798800000000 12150.489299999999 0.000000000000 -4646.631840000000 2941.075680000000 34734.371099999997 7136.731930000000 2793.996340000000 4646.631840000000 0.000000000000 -11430.798800000000 7136.731930000000 6934.133790000000 39 42 60 3952.000000000000 0.000000000000 0.000000000000 0.000000000000 9900.319340000000 -232.717117000000 0.000000000000 3952.000000000000 0.000000000000 -9900.319340000000 0.000000000000 2912.918950000000 0.000000000000 0.000000000000 3952.000000000000 232.717117000000 -2912.918950000000 0.000000000000 0.000000000000 -9900.319340000000 232.717117000000 26195.388700000000 -211.514130000000 -7409.216800000000 9900.319340000000 0.000000000000 -2912.918950000000 -211.514130000000 27966.322300000000 -147.272522000000 -232.717117000000 2912.918950000000 0.000000000000 -7409.216800000000 -147.272522000000 3149.674800000000 39 43 60 4154.000000000000 0.000000000000 0.000000000000 0.000000000000 12740.903300000000 2165.620360000000 0.000000000000 4154.000000000000 0.000000000000 -12740.903300000000 0.000000000000 3067.984620000000 0.000000000000 0.000000000000 4154.000000000000 -2165.620360000000 -3067.984620000000 0.000000000000 0.000000000000 -12740.903300000000 -2165.620360000000 41238.757799999999 1515.733760000000 -9453.757809999999 12740.903300000000 0.000000000000 -3067.984620000000 1515.733760000000 41715.281300000002 6884.963380000000 2165.620360000000 3067.984620000000 0.000000000000 -9453.757809999999 6884.963380000000 4437.870120000000 39 44 60 4572.000000000000 0.000000000000 0.000000000000 0.000000000000 14648.390600000001 4367.178710000000 0.000000000000 4572.000000000000 0.000000000000 -14648.390600000001 0.000000000000 1331.026980000000 0.000000000000 0.000000000000 4572.000000000000 -4367.178710000000 -1331.026980000000 0.000000000000 0.000000000000 -14648.390600000001 -4367.178710000000 51378.851600000002 1167.613770000000 -4332.412110000000 14648.390600000001 0.000000000000 -1331.026980000000 1167.613770000000 47636.082000000002 13916.724600000000 4367.178710000000 1331.026980000000 0.000000000000 -4332.412110000000 13916.724600000000 5061.271970000000 39 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11757.517599999999 -1496.295410000000 0.000000000000 5000.000000000000 0.000000000000 -11757.517599999999 0.000000000000 2103.458250000000 0.000000000000 0.000000000000 5000.000000000000 1496.295410000000 -2103.458250000000 0.000000000000 0.000000000000 -11757.517599999999 1496.295410000000 29131.992200000001 -450.744568000000 -4942.133790000000 11757.517599999999 0.000000000000 -2103.458250000000 -450.744568000000 29736.708999999999 -3283.761720000000 -1496.295410000000 2103.458250000000 0.000000000000 -4942.133790000000 -3283.761720000000 2261.824460000000 39 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12556.591800000000 -826.630920000000 0.000000000000 5000.000000000000 0.000000000000 -12556.591800000000 0.000000000000 2030.567500000000 0.000000000000 0.000000000000 5000.000000000000 826.630920000000 -2030.567500000000 0.000000000000 0.000000000000 -12556.591800000000 826.630920000000 32683.304700000001 -213.818558000000 -5137.827640000000 12556.591800000000 0.000000000000 -2030.567500000000 -213.818558000000 33634.488299999997 -1790.142820000000 -826.630920000000 2030.567500000000 0.000000000000 -5137.827640000000 -1790.142820000000 1930.373170000000 40 42 60 3881.000000000000 0.000000000000 0.000000000000 0.000000000000 8825.829100000001 993.517151000000 0.000000000000 3881.000000000000 0.000000000000 -8825.829100000001 0.000000000000 2862.564700000000 0.000000000000 0.000000000000 3881.000000000000 -993.517151000000 -2862.564700000000 0.000000000000 0.000000000000 -8825.829100000001 -993.517151000000 21134.947300000000 843.375061000000 -6644.305660000000 8825.829100000001 0.000000000000 -2862.564700000000 843.375061000000 22870.755900000000 2584.539310000000 993.517151000000 2862.564700000000 0.000000000000 -6644.305660000000 2584.539310000000 2885.107180000000 40 43 60 2241.000000000000 0.000000000000 0.000000000000 0.000000000000 5929.491700000000 1390.010990000000 0.000000000000 2241.000000000000 0.000000000000 -5929.491700000000 0.000000000000 1699.347050000000 0.000000000000 0.000000000000 2241.000000000000 -1390.010990000000 -1699.347050000000 0.000000000000 0.000000000000 -5929.491700000000 -1390.010990000000 16756.306600000000 1039.006100000000 -4493.267090000000 5929.491700000000 0.000000000000 -1699.347050000000 1039.006100000000 17125.027300000002 3740.952390000000 1390.010990000000 1699.347050000000 0.000000000000 -4493.267090000000 3740.952390000000 2376.483150000000 40 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10510.901400000001 -189.581512000000 0.000000000000 5000.000000000000 0.000000000000 -10510.901400000001 0.000000000000 2217.711670000000 0.000000000000 0.000000000000 5000.000000000000 189.581512000000 -2217.711670000000 0.000000000000 0.000000000000 -10510.901400000001 189.581512000000 23030.119100000000 65.377952600000 -4614.270510000000 10510.901400000001 0.000000000000 -2217.711670000000 65.377952600000 23989.271499999999 -172.780090000000 -189.581512000000 2217.711670000000 0.000000000000 -4614.270510000000 -172.780090000000 1722.501830000000 41 43 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14238.018599999999 2132.388670000000 0.000000000000 5000.000000000000 0.000000000000 -14238.018599999999 0.000000000000 4081.940430000000 0.000000000000 0.000000000000 5000.000000000000 -2132.388670000000 -4081.940430000000 0.000000000000 0.000000000000 -14238.018599999999 -2132.388670000000 42510.332000000002 1072.122440000000 -12112.729499999999 14238.018599999999 0.000000000000 -4081.940430000000 1072.122440000000 45462.527300000002 5927.166500000000 2132.388670000000 4081.940430000000 0.000000000000 -12112.729499999999 5927.166500000000 6070.634280000000 41 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13548.798800000000 157.840744000000 0.000000000000 5000.000000000000 0.000000000000 -13548.798800000000 0.000000000000 5690.479490000000 0.000000000000 0.000000000000 5000.000000000000 -157.840744000000 -5690.479490000000 0.000000000000 0.000000000000 -13548.798800000000 -157.840744000000 39230.148399999998 286.772339000000 -15745.710900000000 13548.798800000000 0.000000000000 -5690.479490000000 286.772339000000 45120.132799999999 1413.531250000000 157.840744000000 5690.479490000000 0.000000000000 -15745.710900000000 1413.531250000000 7600.519040000000 42 45 60 4390.000000000000 0.000000000000 0.000000000000 0.000000000000 11742.430700000001 -978.474976000000 0.000000000000 4390.000000000000 0.000000000000 -11742.430700000001 0.000000000000 -1599.536250000000 0.000000000000 0.000000000000 4390.000000000000 978.474976000000 1599.536250000000 0.000000000000 0.000000000000 -11742.430700000001 978.474976000000 33337.523399999998 215.853165000000 3774.606690000000 11742.430700000001 0.000000000000 1599.536250000000 215.853165000000 33834.917999999998 -2562.180180000000 -978.474976000000 -1599.536250000000 0.000000000000 3774.606690000000 -2562.180180000000 1503.995480000000 42 46 60 3680.000000000000 0.000000000000 0.000000000000 0.000000000000 7698.459960000000 -514.162598000000 0.000000000000 3680.000000000000 0.000000000000 -7698.459960000000 0.000000000000 -2549.112300000000 0.000000000000 0.000000000000 3680.000000000000 514.162598000000 2549.112300000000 0.000000000000 0.000000000000 -7698.459960000000 514.162598000000 17252.939500000000 43.932224300000 5477.922360000000 7698.459960000000 0.000000000000 2549.112300000000 43.932224300000 18660.261699999999 -810.716492000000 -514.162598000000 -2549.112300000000 0.000000000000 5477.922360000000 -810.716492000000 2897.297610000000 42 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12228.829100000001 -1510.144900000000 0.000000000000 5000.000000000000 0.000000000000 -12228.829100000001 0.000000000000 -2018.995240000000 0.000000000000 0.000000000000 5000.000000000000 1510.144900000000 2018.995240000000 0.000000000000 0.000000000000 -12228.829100000001 1510.144900000000 32639.714800000002 480.873810000000 4915.670410000000 12228.829100000001 0.000000000000 2018.995240000000 480.873810000000 33022.191400000003 -3349.829100000000 -1510.144900000000 -2018.995240000000 0.000000000000 4915.670410000000 -3349.829100000000 1905.712040000000 43 44 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14008.915000000001 4293.379390000000 0.000000000000 5000.000000000000 0.000000000000 -14008.915000000001 0.000000000000 -2421.150630000000 0.000000000000 0.000000000000 5000.000000000000 -4293.379390000000 2421.150630000000 0.000000000000 0.000000000000 -14008.915000000001 -4293.379390000000 46223.968800000002 -3303.045650000000 5759.930180000000 14008.915000000001 0.000000000000 2421.150630000000 -3303.045650000000 43598.226600000002 11286.935500000000 4293.379390000000 -2421.150630000000 0.000000000000 5759.930180000000 11286.935500000000 9923.015630000000 43 45 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13766.702100000000 -1086.780030000000 0.000000000000 5000.000000000000 0.000000000000 -13766.702100000000 0.000000000000 -3511.504880000000 0.000000000000 0.000000000000 5000.000000000000 1086.780030000000 3511.504880000000 0.000000000000 0.000000000000 -13766.702100000000 1086.780030000000 43518.066400000003 -849.126282000000 9088.485350000001 13766.702100000000 0.000000000000 3511.504880000000 -849.126282000000 42177.910199999998 -3624.960210000000 -1086.780030000000 -3511.504880000000 0.000000000000 9088.485350000001 -3624.960210000000 8372.059569999999 43 47 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14059.043000000000 -4157.636230000000 0.000000000000 5000.000000000000 0.000000000000 -14059.043000000000 0.000000000000 -2932.684330000000 0.000000000000 0.000000000000 5000.000000000000 4157.636230000000 2932.684330000000 0.000000000000 0.000000000000 -14059.043000000000 4157.636230000000 44314.429700000001 1949.315310000000 7680.291990000000 14059.043000000000 0.000000000000 2932.684330000000 1949.315310000000 42906.921900000001 -12106.972700000000 -4157.636230000000 -2932.684330000000 0.000000000000 7680.291990000000 -12106.972700000000 6334.587400000000 43 48 60 4848.000000000000 0.000000000000 0.000000000000 0.000000000000 14763.438500000000 -4832.247070000000 0.000000000000 4848.000000000000 0.000000000000 -14763.438500000000 0.000000000000 68.680938700000 0.000000000000 0.000000000000 4848.000000000000 4832.247070000000 -68.680938700000 0.000000000000 0.000000000000 -14763.438500000000 4832.247070000000 50652.980499999998 -245.443222000000 -765.327820000000 14763.438500000000 0.000000000000 -68.680938700000 -245.443222000000 46690.359400000001 -14900.129900000000 -4832.247070000000 68.680938700000 0.000000000000 -765.327820000000 -14900.129900000000 5828.386720000000 43 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14897.814500000000 -4864.785640000000 0.000000000000 5000.000000000000 0.000000000000 -14897.814500000000 0.000000000000 -1439.632200000000 0.000000000000 0.000000000000 5000.000000000000 4864.785640000000 1439.632200000000 0.000000000000 0.000000000000 -14897.814500000000 4864.785640000000 50165.042999999998 1156.028440000000 3790.139890000000 14897.814500000000 0.000000000000 1439.632200000000 1156.028440000000 46409.390599999999 -14789.571300000000 -4864.785640000000 -1439.632200000000 0.000000000000 3790.139890000000 -14789.571300000000 6016.588380000000 43 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15980.224600000000 -4066.955570000000 0.000000000000 5000.000000000000 0.000000000000 -15980.224600000000 0.000000000000 1513.726560000000 0.000000000000 0.000000000000 5000.000000000000 4066.955570000000 -1513.726560000000 0.000000000000 0.000000000000 -15980.224600000000 4066.955570000000 55275.027300000002 -852.145996000000 -5038.317380000000 15980.224600000000 0.000000000000 -1513.726560000000 -852.145996000000 53870.000000000000 -12903.411099999999 -4066.955570000000 1513.726560000000 0.000000000000 -5038.317380000000 -12903.411099999999 6306.903810000000 43 51 60 4765.000000000000 0.000000000000 0.000000000000 0.000000000000 15490.079100000001 -3202.718020000000 0.000000000000 4765.000000000000 0.000000000000 -15490.079100000001 0.000000000000 3080.031740000000 0.000000000000 0.000000000000 4765.000000000000 3202.718020000000 -3080.031740000000 0.000000000000 0.000000000000 -15490.079100000001 3202.718020000000 53240.460899999998 -1806.355590000000 -10070.811500000000 15490.079100000001 0.000000000000 -3080.031740000000 -1806.355590000000 52831.839800000002 -10299.053700000000 -3202.718020000000 3080.031740000000 0.000000000000 -10070.811500000000 -10299.053700000000 5072.383790000000 45 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13188.163100000000 -5616.178220000000 0.000000000000 5000.000000000000 0.000000000000 -13188.163100000000 0.000000000000 3243.593260000000 0.000000000000 0.000000000000 5000.000000000000 5616.178220000000 -3243.593260000000 0.000000000000 0.000000000000 -13188.163100000000 5616.178220000000 42351.761700000003 -4087.084470000000 -9699.458979999999 13188.163100000000 0.000000000000 -3243.593260000000 -4087.084470000000 39704.382799999999 -15132.079100000001 -5616.178220000000 3243.593260000000 0.000000000000 -9699.458979999999 -15132.079100000001 10391.063500000000 45 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13260.615200000000 -5510.702640000000 0.000000000000 5000.000000000000 0.000000000000 -13260.615200000000 0.000000000000 2649.204830000000 0.000000000000 0.000000000000 5000.000000000000 5510.702640000000 -2649.204830000000 0.000000000000 0.000000000000 -13260.615200000000 5510.702640000000 42481.199200000003 -3409.959720000000 -8142.610350000000 13260.615200000000 0.000000000000 -2649.204830000000 -3409.959720000000 39606.054700000001 -14909.619100000000 -5510.702640000000 2649.204830000000 0.000000000000 -8142.610350000000 -14909.619100000000 9706.233399999999 45 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14700.704100000001 -6311.061520000000 0.000000000000 5000.000000000000 0.000000000000 -14700.704100000001 0.000000000000 4756.823730000000 0.000000000000 0.000000000000 5000.000000000000 6311.061520000000 -4756.823730000000 0.000000000000 0.000000000000 -14700.704100000001 6311.061520000000 51986.007799999999 -6184.980470000000 -14403.557600000000 14700.704100000001 0.000000000000 -4756.823730000000 -6184.980470000000 48963.269500000002 -18732.119100000000 -6311.061520000000 4756.823730000000 0.000000000000 -14403.557600000000 -18732.119100000000 13125.329100000001 46 48 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13260.681600000000 -2769.214600000000 0.000000000000 5000.000000000000 0.000000000000 -13260.681600000000 0.000000000000 2028.545900000000 0.000000000000 0.000000000000 5000.000000000000 2769.214600000000 -2028.545900000000 0.000000000000 0.000000000000 -13260.681600000000 2769.214600000000 37587.539100000002 -961.320313000000 -5397.238770000000 13260.681600000000 0.000000000000 -2028.545900000000 -961.320313000000 37140.453099999999 -7181.509280000000 -2769.214600000000 2028.545900000000 0.000000000000 -5397.238770000000 -7181.509280000000 3224.652100000000 46 49 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14002.946300000000 -2110.958500000000 0.000000000000 5000.000000000000 0.000000000000 -14002.946300000000 0.000000000000 1963.077030000000 0.000000000000 0.000000000000 5000.000000000000 2110.958500000000 -1963.077030000000 0.000000000000 0.000000000000 -14002.946300000000 2110.958500000000 40970.574200000003 -725.630310000000 -5531.367680000000 14002.946300000000 0.000000000000 -1963.077030000000 -725.630310000000 41233.867200000001 -5671.750490000000 -2110.958500000000 1963.077030000000 0.000000000000 -5531.367680000000 -5671.750490000000 2610.482910000000 47 50 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14438.252899999999 1232.572140000000 0.000000000000 5000.000000000000 0.000000000000 -14438.252899999999 0.000000000000 5362.256840000000 0.000000000000 0.000000000000 5000.000000000000 -1232.572140000000 -5362.256840000000 0.000000000000 0.000000000000 -14438.252899999999 -1232.572140000000 44497.109400000001 1607.128540000000 -16097.153300000000 14438.252899999999 0.000000000000 -5362.256840000000 1607.128540000000 49328.378900000003 4412.250000000000 1232.572140000000 5362.256840000000 0.000000000000 -16097.153300000000 4412.250000000000 7438.226070000000 48 51 60 4835.000000000000 0.000000000000 0.000000000000 0.000000000000 11738.195299999999 1576.688480000000 0.000000000000 4835.000000000000 0.000000000000 -11738.195299999999 0.000000000000 5135.196290000000 0.000000000000 0.000000000000 4835.000000000000 -1576.688480000000 -5135.196290000000 0.000000000000 0.000000000000 -11738.195299999999 -1576.688480000000 29783.015599999999 1885.934690000000 -12709.145500000001 11738.195299999999 0.000000000000 -5135.196290000000 1885.934690000000 34606.449200000003 4211.105960000000 1576.688480000000 5135.196290000000 0.000000000000 -12709.145500000001 4211.105960000000 6543.625000000000 50 59 60 4970.000000000000 0.000000000000 0.000000000000 0.000000000000 13643.096700000000 2474.203130000000 0.000000000000 4970.000000000000 0.000000000000 -13643.096700000000 0.000000000000 6641.798340000000 0.000000000000 0.000000000000 4970.000000000000 -2474.203130000000 -6641.798340000000 0.000000000000 0.000000000000 -13643.096700000000 -2474.203130000000 40561.187500000000 3380.948490000000 -18284.871100000000 13643.096700000000 0.000000000000 -6641.798340000000 3380.948490000000 47508.136700000003 7049.155760000000 2474.203130000000 6641.798340000000 0.000000000000 -18284.871100000000 7049.155760000000 11033.333000000001 51 53 60 4296.000000000000 0.000000000000 0.000000000000 0.000000000000 9067.278319999999 -323.625458000000 0.000000000000 4296.000000000000 0.000000000000 -9067.278319999999 0.000000000000 1525.538570000000 0.000000000000 0.000000000000 4296.000000000000 323.625458000000 -1525.538570000000 0.000000000000 0.000000000000 -9067.278319999999 323.625458000000 20264.566400000000 -30.365810400000 -3204.583010000000 9067.278319999999 0.000000000000 -1525.538570000000 -30.365810400000 20513.324199999999 -622.278381000000 -323.625458000000 1525.538570000000 0.000000000000 -3204.583010000000 -622.278381000000 946.796387000000 52 53 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7573.976070000000 -753.450867000000 0.000000000000 5000.000000000000 0.000000000000 -7573.976070000000 0.000000000000 -104.280739000000 0.000000000000 0.000000000000 5000.000000000000 753.450867000000 104.280739000000 0.000000000000 0.000000000000 -7573.976070000000 753.450867000000 12565.791999999999 108.186157000000 524.989807000000 7573.976070000000 0.000000000000 104.280739000000 108.186157000000 12394.914100000000 -1187.771480000000 -753.450867000000 -104.280739000000 0.000000000000 524.989807000000 -1187.771480000000 758.470154000000 52 54 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7683.916990000000 177.771393000000 0.000000000000 5000.000000000000 0.000000000000 -7683.916990000000 0.000000000000 226.955139000000 0.000000000000 0.000000000000 5000.000000000000 -177.771393000000 -226.955139000000 0.000000000000 0.000000000000 -7683.916990000000 -177.771393000000 12779.471700000000 183.435959000000 -290.398193000000 7683.916990000000 0.000000000000 -226.955139000000 183.435959000000 12381.039100000000 457.740112000000 177.771393000000 226.955139000000 0.000000000000 -290.398193000000 457.740112000000 792.272949000000 52 55 60 2332.000000000000 0.000000000000 0.000000000000 0.000000000000 3833.668950000000 846.191895000000 0.000000000000 2332.000000000000 0.000000000000 -3833.668950000000 0.000000000000 296.075043000000 0.000000000000 0.000000000000 2332.000000000000 -846.191895000000 -296.075043000000 0.000000000000 0.000000000000 -3833.668950000000 -846.191895000000 6912.802250000000 139.729431000000 -478.147614000000 3833.668950000000 0.000000000000 -296.075043000000 139.729431000000 6623.047850000000 1491.506230000000 846.191895000000 296.075043000000 0.000000000000 -478.147614000000 1491.506230000000 567.400696000000 52 56 60 1401.000000000000 0.000000000000 0.000000000000 0.000000000000 2457.593990000000 767.680237000000 0.000000000000 1401.000000000000 0.000000000000 -2457.593990000000 0.000000000000 235.618713000000 0.000000000000 0.000000000000 1401.000000000000 -767.680237000000 -235.618713000000 0.000000000000 0.000000000000 -2457.593990000000 -767.680237000000 4864.123540000000 120.033005000000 -424.498138000000 2457.593990000000 0.000000000000 -235.618713000000 120.033005000000 4551.175290000000 1389.417600000000 767.680237000000 235.618713000000 0.000000000000 -424.498138000000 1389.417600000000 589.222229000000 52 57 60 2430.000000000000 0.000000000000 0.000000000000 0.000000000000 4092.546390000000 957.316284000000 0.000000000000 2430.000000000000 0.000000000000 -4092.546390000000 0.000000000000 104.028160000000 0.000000000000 0.000000000000 2430.000000000000 -957.316284000000 -104.028160000000 0.000000000000 0.000000000000 -4092.546390000000 -957.316284000000 7613.817380000000 26.381458300000 -36.164314300000 4092.546390000000 0.000000000000 -104.028160000000 26.381458300000 7454.116210000000 1715.910030000000 957.316284000000 104.028160000000 0.000000000000 -36.164314300000 1715.910030000000 773.485840000000 52 58 60 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8134.733890000000 773.173218000000 0.000000000000 5000.000000000000 0.000000000000 -8134.733890000000 0.000000000000 -279.458344000000 0.000000000000 0.000000000000 5000.000000000000 -773.173218000000 279.458344000000 0.000000000000 0.000000000000 -8134.733890000000 -773.173218000000 14805.827100000000 -84.538085900000 1118.455200000000 8134.733890000000 0.000000000000 279.458344000000 -84.538085900000 14986.537100000000 1452.378300000000 773.173218000000 -279.458344000000 0.000000000000 1118.455200000000 1452.378300000000 930.529663000000 53 57 60 2039.000000000000 0.000000000000 0.000000000000 0.000000000000 2228.794190000000 687.997437000000 0.000000000000 2039.000000000000 0.000000000000 -2228.794190000000 0.000000000000 -307.483459000000 0.000000000000 0.000000000000 2039.000000000000 -687.997437000000 307.483459000000 0.000000000000 0.000000000000 -2228.794190000000 -687.997437000000 2785.197750000000 -146.361618000000 471.187714000000 2228.794190000000 0.000000000000 307.483459000000 -146.361618000000 2826.323970000000 785.298218000000 687.997437000000 -307.483459000000 0.000000000000 471.187714000000 785.298218000000 544.978088000000 56 59 60 3755.000000000000 0.000000000000 0.000000000000 0.000000000000 5648.319820000000 -782.598816000000 0.000000000000 3755.000000000000 0.000000000000 -5648.319820000000 0.000000000000 -2122.484380000000 0.000000000000 0.000000000000 3755.000000000000 782.598816000000 2122.484380000000 0.000000000000 0.000000000000 -5648.319820000000 782.598816000000 9315.302729999999 336.481140000000 2950.756590000000 5648.319820000000 0.000000000000 2122.484380000000 336.481140000000 10509.194299999999 -1318.769290000000 -782.598816000000 -2122.484380000000 0.000000000000 2950.756590000000 -1318.769290000000 1842.692020000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-hotel_uc-scan3/gt.info ================================================ 0 4 55 3036.000000000000 0.000000000000 0.000000000000 0.000000000000 5390.793950000000 86.657234200000 0.000000000000 3036.000000000000 0.000000000000 -5390.793950000000 0.000000000000 2957.440190000000 0.000000000000 0.000000000000 3036.000000000000 -86.657234200000 -2957.440190000000 0.000000000000 0.000000000000 -5390.793950000000 -86.657234200000 10437.653300000000 44.483638800000 -5393.543950000000 5390.793950000000 0.000000000000 -2957.440190000000 44.483638800000 13136.426799999999 32.937782300000 86.657234200000 2957.440190000000 0.000000000000 -5393.543950000000 32.937782300000 3277.774660000000 0 9 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10310.234399999999 -752.785706000000 0.000000000000 5000.000000000000 0.000000000000 -10310.234399999999 0.000000000000 4422.357420000000 0.000000000000 0.000000000000 5000.000000000000 752.785706000000 -4422.357420000000 0.000000000000 0.000000000000 -10310.234399999999 752.785706000000 22522.056600000000 -448.033356000000 -9245.542970000000 10310.234399999999 0.000000000000 -4422.357420000000 -448.033356000000 26108.986300000000 -1530.019900000000 -752.785706000000 4422.357420000000 0.000000000000 -9245.542970000000 -1530.019900000000 5241.488280000000 0 11 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12970.842800000000 -405.874084000000 0.000000000000 5000.000000000000 0.000000000000 -12970.842800000000 0.000000000000 -4137.557130000000 0.000000000000 0.000000000000 5000.000000000000 405.874084000000 4137.557130000000 0.000000000000 0.000000000000 -12970.842800000000 405.874084000000 35778.132799999999 129.222198000000 11542.370100000000 12970.842800000000 0.000000000000 4137.557130000000 129.222198000000 39465.968800000002 -409.912903000000 -405.874084000000 -4137.557130000000 0.000000000000 11542.370100000000 -409.912903000000 4565.705080000000 0 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8961.325199999999 -768.242920000000 0.000000000000 5000.000000000000 0.000000000000 -8961.325199999999 0.000000000000 1299.983280000000 0.000000000000 0.000000000000 5000.000000000000 768.242920000000 -1299.983280000000 0.000000000000 0.000000000000 -8961.325199999999 768.242920000000 18130.503900000000 27.897968300000 -1517.163820000000 8961.325199999999 0.000000000000 -1299.983280000000 27.897968300000 19900.726600000002 -1261.809940000000 -768.242920000000 1299.983280000000 0.000000000000 -1517.163820000000 -1261.809940000000 2856.395510000000 0 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9406.625000000000 -1.015169500000 0.000000000000 5000.000000000000 0.000000000000 -9406.625000000000 0.000000000000 2881.456540000000 0.000000000000 0.000000000000 5000.000000000000 1.015169500000 -2881.456540000000 0.000000000000 0.000000000000 -9406.625000000000 1.015169500000 19428.136699999999 779.438782000000 -5801.686520000000 9406.625000000000 0.000000000000 -2881.456540000000 779.438782000000 22053.652300000002 129.724289000000 -1.015169500000 2881.456540000000 0.000000000000 -5801.686520000000 129.724289000000 4270.588380000000 0 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11453.597700000000 -1304.604610000000 0.000000000000 5000.000000000000 0.000000000000 -11453.597700000000 0.000000000000 -2891.796390000000 0.000000000000 0.000000000000 5000.000000000000 1304.604610000000 2891.796390000000 0.000000000000 0.000000000000 -11453.597700000000 1304.604610000000 27927.652300000002 758.947266000000 7001.697270000000 11453.597700000000 0.000000000000 2891.796390000000 758.947266000000 29686.123000000000 -2706.846680000000 -1304.604610000000 -2891.796390000000 0.000000000000 7001.697270000000 -2706.846680000000 2635.546390000000 0 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10724.731400000001 -2350.695800000000 0.000000000000 5000.000000000000 0.000000000000 -10724.731400000001 0.000000000000 622.704102000000 0.000000000000 0.000000000000 5000.000000000000 2350.695800000000 -622.704102000000 0.000000000000 0.000000000000 -10724.731400000001 2350.695800000000 24882.701200000000 -581.438721000000 -1698.226070000000 10724.731400000001 0.000000000000 -622.704102000000 -581.438721000000 25031.632799999999 -5056.879880000000 -2350.695800000000 622.704102000000 0.000000000000 -1698.226070000000 -5056.879880000000 2849.907710000000 0 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13191.941400000000 -106.685417000000 0.000000000000 5000.000000000000 0.000000000000 -13191.941400000000 0.000000000000 -4048.364990000000 0.000000000000 0.000000000000 5000.000000000000 106.685417000000 4048.364990000000 0.000000000000 0.000000000000 -13191.941400000000 106.685417000000 36915.523399999998 -192.919525000000 11442.727500000001 13191.941400000000 0.000000000000 4048.364990000000 -192.919525000000 40171.128900000003 424.619598000000 -106.685417000000 -4048.364990000000 0.000000000000 11442.727500000001 424.619598000000 4384.696290000000 0 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12599.415000000001 -1134.307370000000 0.000000000000 5000.000000000000 0.000000000000 -12599.415000000001 0.000000000000 -4279.775880000000 0.000000000000 0.000000000000 5000.000000000000 1134.307370000000 4279.775880000000 0.000000000000 0.000000000000 -12599.415000000001 1134.307370000000 33420.699200000003 824.950623000000 11372.878900000000 12599.415000000001 0.000000000000 4279.775880000000 824.950623000000 37036.257799999999 -2498.044190000000 -1134.307370000000 -4279.775880000000 0.000000000000 11372.878900000000 -2498.044190000000 4607.609860000000 1 9 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12334.933600000000 -1737.344240000000 0.000000000000 5000.000000000000 0.000000000000 -12334.933600000000 0.000000000000 4676.125000000000 0.000000000000 0.000000000000 5000.000000000000 1737.344240000000 -4676.125000000000 0.000000000000 0.000000000000 -12334.933600000000 1737.344240000000 32228.441400000000 -1500.991820000000 -11761.855500000000 12334.933600000000 0.000000000000 -4676.125000000000 -1500.991820000000 35566.265599999999 -4187.543460000000 -1737.344240000000 4676.125000000000 0.000000000000 -11761.855500000000 -4187.543460000000 6184.587400000000 1 11 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11847.176799999999 -724.729614000000 0.000000000000 5000.000000000000 0.000000000000 -11847.176799999999 0.000000000000 -3566.491210000000 0.000000000000 0.000000000000 5000.000000000000 724.729614000000 3566.491210000000 0.000000000000 0.000000000000 -11847.176799999999 724.729614000000 30619.925800000001 504.102936000000 8690.521479999999 11847.176799999999 0.000000000000 3566.491210000000 504.102936000000 33402.570299999999 -1035.270750000000 -724.729614000000 -3566.491210000000 0.000000000000 8690.521479999999 -1035.270750000000 3649.609620000000 1 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9234.579100000001 -1518.321780000000 0.000000000000 5000.000000000000 0.000000000000 -9234.579100000001 0.000000000000 -1337.934330000000 0.000000000000 0.000000000000 5000.000000000000 1518.321780000000 1337.934330000000 0.000000000000 0.000000000000 -9234.579100000001 1518.321780000000 18908.189500000000 581.682373000000 1854.483520000000 9234.579100000001 0.000000000000 1337.934330000000 581.682373000000 19915.996100000000 -2482.646970000000 -1518.321780000000 -1337.934330000000 0.000000000000 1854.483520000000 -2482.646970000000 2262.413820000000 1 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9404.774410000000 -1214.178590000000 0.000000000000 5000.000000000000 0.000000000000 -9404.774410000000 0.000000000000 210.932419000000 0.000000000000 0.000000000000 5000.000000000000 1214.178590000000 -210.932419000000 0.000000000000 0.000000000000 -9404.774410000000 1214.178590000000 19805.939500000000 707.061951000000 -2105.826900000000 9404.774410000000 0.000000000000 -210.932419000000 707.061951000000 22023.015599999999 -1804.136470000000 -1214.178590000000 210.932419000000 0.000000000000 -2105.826900000000 -1804.136470000000 3630.354740000000 1 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9847.554690000001 -1540.695800000000 0.000000000000 5000.000000000000 0.000000000000 -9847.554690000001 0.000000000000 -3606.402590000000 0.000000000000 0.000000000000 5000.000000000000 1540.695800000000 3606.402590000000 0.000000000000 0.000000000000 -9847.554690000001 1540.695800000000 21558.240200000000 1145.014040000000 7156.488770000000 9847.554690000001 0.000000000000 3606.402590000000 1145.014040000000 24455.168000000001 -2704.438720000000 -1540.695800000000 -3606.402590000000 0.000000000000 7156.488770000000 -2704.438720000000 4004.887940000000 1 36 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11731.768599999999 -640.197083000000 0.000000000000 5000.000000000000 0.000000000000 -11731.768599999999 0.000000000000 2504.656250000000 0.000000000000 0.000000000000 5000.000000000000 640.197083000000 -2504.656250000000 0.000000000000 0.000000000000 -11731.768599999999 640.197083000000 29045.804700000001 -17.136634800000 -6733.769530000000 11731.768599999999 0.000000000000 -2504.656250000000 -17.136634800000 31199.554700000001 -1203.844730000000 -640.197083000000 2504.656250000000 0.000000000000 -6733.769530000000 -1203.844730000000 3474.038820000000 1 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11157.443400000000 -2355.041260000000 0.000000000000 5000.000000000000 0.000000000000 -11157.443400000000 0.000000000000 434.665314000000 0.000000000000 0.000000000000 5000.000000000000 2355.041260000000 -434.665314000000 0.000000000000 0.000000000000 -11157.443400000000 2355.041260000000 27292.912100000001 -702.918274000000 -1536.096070000000 11157.443400000000 0.000000000000 -434.665314000000 -702.918274000000 27321.822300000000 -5367.527830000000 -2355.041260000000 434.665314000000 0.000000000000 -1536.096070000000 -5367.527830000000 2940.218750000000 1 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10963.375000000000 -948.122925000000 0.000000000000 5000.000000000000 0.000000000000 -10963.375000000000 0.000000000000 -3946.181640000000 0.000000000000 0.000000000000 5000.000000000000 948.122925000000 3946.181640000000 0.000000000000 0.000000000000 -10963.375000000000 948.122925000000 26840.107400000001 768.239868000000 8813.123050000000 10963.375000000000 0.000000000000 3946.181640000000 768.239868000000 30119.330099999999 -1287.789310000000 -948.122925000000 -3946.181640000000 0.000000000000 8813.123050000000 -1287.789310000000 4496.575680000000 1 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9920.124019999999 -1621.776000000000 0.000000000000 5000.000000000000 0.000000000000 -9920.124019999999 0.000000000000 -4583.730470000000 0.000000000000 0.000000000000 5000.000000000000 1621.776000000000 4583.730470000000 0.000000000000 0.000000000000 -9920.124019999999 1621.776000000000 21779.919900000001 1451.704830000000 9378.105470000000 9920.124019999999 0.000000000000 4583.730470000000 1451.704830000000 26074.583999999999 -2953.458740000000 -1621.776000000000 -4583.730470000000 0.000000000000 9378.105470000000 -2953.458740000000 5459.058590000000 2 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11650.401400000001 1424.029660000000 0.000000000000 5000.000000000000 0.000000000000 -11650.401400000001 0.000000000000 1611.366580000000 0.000000000000 0.000000000000 5000.000000000000 -1424.029660000000 -1611.366580000000 0.000000000000 0.000000000000 -11650.401400000001 -1424.029660000000 29441.384800000000 1074.081050000000 -4391.162600000000 11650.401400000001 0.000000000000 -1611.366580000000 1074.081050000000 29678.918000000001 4173.725100000000 1424.029660000000 1611.366580000000 0.000000000000 -4391.162600000000 4173.725100000000 2741.790770000000 2 19 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13758.983399999999 3739.022710000000 0.000000000000 5000.000000000000 0.000000000000 -13758.983399999999 0.000000000000 3890.709720000000 0.000000000000 0.000000000000 5000.000000000000 -3739.022710000000 -3890.709720000000 0.000000000000 0.000000000000 -13758.983399999999 -3739.022710000000 41561.296900000001 2879.992680000000 -10696.261699999999 13758.983399999999 0.000000000000 -3890.709720000000 2879.992680000000 41511.230499999998 10526.463900000001 3739.022710000000 3890.709720000000 0.000000000000 -10696.261699999999 10526.463900000001 6805.120120000000 2 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10076.102500000001 34.565284700000 0.000000000000 5000.000000000000 0.000000000000 -10076.102500000001 0.000000000000 676.402100000000 0.000000000000 0.000000000000 5000.000000000000 -34.565284700000 -676.402100000000 0.000000000000 0.000000000000 -10076.102500000001 -34.565284700000 20875.175800000001 240.666794000000 -1652.774780000000 10076.102500000001 0.000000000000 -676.402100000000 240.666794000000 21649.601600000002 302.688995000000 34.565284700000 676.402100000000 0.000000000000 -1652.774780000000 302.688995000000 1062.494260000000 2 21 55 3194.000000000000 0.000000000000 0.000000000000 0.000000000000 6347.353520000000 -273.225128000000 0.000000000000 3194.000000000000 0.000000000000 -6347.353520000000 0.000000000000 -1241.491700000000 0.000000000000 0.000000000000 3194.000000000000 273.225128000000 1241.491700000000 0.000000000000 0.000000000000 -6347.353520000000 273.225128000000 12854.401400000001 131.362122000000 2607.272710000000 6347.353520000000 0.000000000000 1241.491700000000 131.362122000000 13845.090800000000 -479.409210000000 -273.225128000000 -1241.491700000000 0.000000000000 2607.272710000000 -479.409210000000 1107.878540000000 2 36 55 4375.000000000000 0.000000000000 0.000000000000 0.000000000000 10365.854499999999 1423.728270000000 0.000000000000 4375.000000000000 0.000000000000 -10365.854499999999 0.000000000000 2796.865480000000 0.000000000000 0.000000000000 4375.000000000000 -1423.728270000000 -2796.865480000000 0.000000000000 0.000000000000 -10365.854499999999 -1423.728270000000 25933.003900000000 1500.996580000000 -7190.942380000000 10365.854499999999 0.000000000000 -2796.865480000000 1500.996580000000 27841.828099999999 3761.161620000000 1423.728270000000 2796.865480000000 0.000000000000 -7190.942380000000 3761.161620000000 3785.923340000000 2 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11763.998000000000 472.754852000000 0.000000000000 5000.000000000000 0.000000000000 -11763.998000000000 0.000000000000 2628.931400000000 0.000000000000 0.000000000000 5000.000000000000 -472.754852000000 -2628.931400000000 0.000000000000 0.000000000000 -11763.998000000000 -472.754852000000 28956.826200000000 220.635834000000 -6528.176760000000 11763.998000000000 0.000000000000 -2628.931400000000 220.635834000000 30927.453099999999 1459.182250000000 472.754852000000 2628.931400000000 0.000000000000 -6528.176760000000 1459.182250000000 2797.046880000000 2 47 55 4611.000000000000 0.000000000000 0.000000000000 0.000000000000 9435.162109999999 -1995.289310000000 0.000000000000 4611.000000000000 0.000000000000 -9435.162109999999 0.000000000000 -4155.366210000000 0.000000000000 0.000000000000 4611.000000000000 1995.289310000000 4155.366210000000 0.000000000000 0.000000000000 -9435.162109999999 1995.289310000000 21154.386699999999 2045.953000000000 8793.295899999999 9435.162109999999 0.000000000000 4155.366210000000 2045.953000000000 23952.353500000001 -4044.167720000000 -1995.289310000000 -4155.366210000000 0.000000000000 8793.295899999999 -4044.167720000000 5662.859860000000 3 11 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13300.346700000000 -2045.811520000000 0.000000000000 5000.000000000000 0.000000000000 -13300.346700000000 0.000000000000 -910.203796000000 0.000000000000 0.000000000000 5000.000000000000 2045.811520000000 910.203796000000 0.000000000000 0.000000000000 -13300.346700000000 2045.811520000000 37951.453099999999 475.961639000000 2569.746580000000 13300.346700000000 0.000000000000 910.203796000000 475.961639000000 37612.527300000002 -5023.038570000000 -2045.811520000000 -910.203796000000 0.000000000000 2569.746580000000 -5023.038570000000 1896.570430000000 3 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9840.051760000000 -2074.973630000000 0.000000000000 5000.000000000000 0.000000000000 -9840.051760000000 0.000000000000 2700.473630000000 0.000000000000 0.000000000000 5000.000000000000 2074.973630000000 -2700.473630000000 0.000000000000 0.000000000000 -9840.051760000000 2074.973630000000 21801.406299999999 -429.604401000000 -4909.804200000000 9840.051760000000 0.000000000000 -2700.473630000000 -429.604401000000 23957.240200000000 -4248.511230000000 -2074.973630000000 2700.473630000000 0.000000000000 -4909.804200000000 -4248.511230000000 5081.424800000000 3 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9054.085940000001 -1983.359620000000 0.000000000000 5000.000000000000 0.000000000000 -9054.085940000001 0.000000000000 3199.093990000000 0.000000000000 0.000000000000 5000.000000000000 1983.359620000000 -3199.093990000000 0.000000000000 0.000000000000 -9054.085940000001 1983.359620000000 18454.677700000000 -394.716980000000 -5587.797850000000 9054.085940000001 0.000000000000 -3199.093990000000 -394.716980000000 21422.921900000001 -3866.965820000000 -1983.359620000000 3199.093990000000 0.000000000000 -5587.797850000000 -3866.965820000000 5948.774410000000 3 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11436.860400000000 -2887.709470000000 0.000000000000 5000.000000000000 0.000000000000 -11436.860400000000 0.000000000000 -915.812134000000 0.000000000000 0.000000000000 5000.000000000000 2887.709470000000 915.812134000000 0.000000000000 0.000000000000 -11436.860400000000 2887.709470000000 28844.771499999999 609.246094000000 2173.156250000000 11436.860400000000 0.000000000000 915.812134000000 609.246094000000 28110.064500000000 -6476.497070000000 -2887.709470000000 -915.812134000000 0.000000000000 2173.156250000000 -6476.497070000000 2676.408200000000 3 36 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10794.919900000001 -2007.823120000000 0.000000000000 5000.000000000000 0.000000000000 -10794.919900000001 0.000000000000 4592.256350000000 0.000000000000 0.000000000000 5000.000000000000 2007.823120000000 -4592.256350000000 0.000000000000 0.000000000000 -10794.919900000001 2007.823120000000 25304.500000000000 -1484.553710000000 -10232.996100000000 10794.919900000001 0.000000000000 -4592.256350000000 -1484.553710000000 29734.363300000001 -4242.125980000000 -2007.823120000000 4592.256350000000 0.000000000000 -10232.996100000000 -4242.125980000000 6787.945310000000 3 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10898.646500000001 -3487.304930000000 0.000000000000 5000.000000000000 0.000000000000 -10898.646500000001 0.000000000000 2185.098880000000 0.000000000000 0.000000000000 5000.000000000000 3487.304930000000 -2185.098880000000 0.000000000000 0.000000000000 -10898.646500000001 3487.304930000000 26873.585899999998 -1874.867920000000 -5142.896480000000 10898.646500000001 0.000000000000 -2185.098880000000 -1874.867920000000 26593.345700000002 -7708.377440000000 -3487.304930000000 2185.098880000000 0.000000000000 -5142.896480000000 -7708.377440000000 4972.225590000000 3 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12026.907200000000 -2422.696290000000 0.000000000000 5000.000000000000 0.000000000000 -12026.907200000000 0.000000000000 2551.332520000000 0.000000000000 0.000000000000 5000.000000000000 2422.696290000000 -2551.332520000000 0.000000000000 0.000000000000 -12026.907200000000 2422.696290000000 31622.753900000000 -1507.333740000000 -6336.448730000000 12026.907200000000 0.000000000000 -2551.332520000000 -1507.333740000000 32070.845700000002 -5412.625980000000 -2422.696290000000 2551.332520000000 0.000000000000 -6336.448730000000 -5412.625980000000 4117.173340000000 3 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12377.476600000000 -2341.559810000000 0.000000000000 5000.000000000000 0.000000000000 -12377.476600000000 0.000000000000 -1409.834840000000 0.000000000000 0.000000000000 5000.000000000000 2341.559810000000 1409.834840000000 0.000000000000 0.000000000000 -12377.476600000000 2341.559810000000 33482.226600000002 771.043091000000 3510.707520000000 12377.476600000000 0.000000000000 1409.834840000000 771.043091000000 33050.812500000000 -5291.554690000000 -2341.559810000000 -1409.834840000000 0.000000000000 3510.707520000000 -5291.554690000000 2416.876460000000 3 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11215.259800000000 -3069.294680000000 0.000000000000 5000.000000000000 0.000000000000 -11215.259800000000 0.000000000000 -1947.545530000000 0.000000000000 0.000000000000 5000.000000000000 3069.294680000000 1947.545530000000 0.000000000000 0.000000000000 -11215.259800000000 3069.294680000000 28006.716799999998 1226.458370000000 4605.611820000000 11215.259800000000 0.000000000000 1947.545530000000 1226.458370000000 27485.021499999999 -6792.086430000000 -3069.294680000000 -1947.545530000000 0.000000000000 4605.611820000000 -6792.086430000000 3298.267580000000 4 7 55 4492.000000000000 0.000000000000 0.000000000000 0.000000000000 7500.963870000000 -1218.230350000000 0.000000000000 4492.000000000000 0.000000000000 -7500.963870000000 0.000000000000 4755.373050000000 0.000000000000 0.000000000000 4492.000000000000 1218.230350000000 -4755.373050000000 0.000000000000 0.000000000000 -7500.963870000000 1218.230350000000 13360.921899999999 -1226.068480000000 -7838.494630000000 7500.963870000000 0.000000000000 -4755.373050000000 -1226.068480000000 18133.744100000000 -1997.258420000000 -1218.230350000000 4755.373050000000 0.000000000000 -7838.494630000000 -1997.258420000000 5978.013670000000 4 8 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8225.639649999999 -2338.068850000000 0.000000000000 5000.000000000000 0.000000000000 -8225.639649999999 0.000000000000 3710.146970000000 0.000000000000 0.000000000000 5000.000000000000 2338.068850000000 -3710.146970000000 0.000000000000 0.000000000000 -8225.639649999999 2338.068850000000 15007.100600000000 -1616.331420000000 -6065.297360000000 8225.639649999999 0.000000000000 -3710.146970000000 -1616.331420000000 17863.962899999999 -3866.785160000000 -2338.068850000000 3710.146970000000 0.000000000000 -6065.297360000000 -3866.785160000000 5289.806640000000 4 10 55 3838.000000000000 0.000000000000 0.000000000000 0.000000000000 7437.901370000000 -1149.973390000000 0.000000000000 3838.000000000000 0.000000000000 -7437.901370000000 0.000000000000 -1944.290650000000 0.000000000000 0.000000000000 3838.000000000000 1149.973390000000 1944.290650000000 0.000000000000 0.000000000000 -7437.901370000000 1149.973390000000 15644.942400000000 663.995911000000 4327.530270000000 7437.901370000000 0.000000000000 1944.290650000000 663.995911000000 16800.855500000001 -2324.462890000000 -1149.973390000000 -1944.290650000000 0.000000000000 4327.530270000000 -2324.462890000000 2694.735350000000 4 19 55 3227.000000000000 0.000000000000 0.000000000000 0.000000000000 6595.129390000000 53.728641500000 0.000000000000 3227.000000000000 0.000000000000 -6595.129390000000 0.000000000000 -1662.585570000000 0.000000000000 0.000000000000 3227.000000000000 -53.728641500000 1662.585570000000 0.000000000000 0.000000000000 -6595.129390000000 -53.728641500000 14429.383800000000 11.222283400000 3589.818120000000 6595.129390000000 0.000000000000 1662.585570000000 11.222283400000 14793.083000000001 -40.894844100000 53.728641500000 -1662.585570000000 0.000000000000 3589.818120000000 -40.894844100000 1759.405760000000 4 38 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8166.796390000000 -1578.204100000000 0.000000000000 5000.000000000000 0.000000000000 -8166.796390000000 0.000000000000 5791.683110000000 0.000000000000 0.000000000000 5000.000000000000 1578.204100000000 -5791.683110000000 0.000000000000 0.000000000000 -8166.796390000000 1578.204100000000 14348.909200000000 -1806.809690000000 -9310.175780000000 8166.796390000000 0.000000000000 -5791.683110000000 -1806.809690000000 20567.960899999998 -2559.220950000000 -1578.204100000000 5791.683110000000 0.000000000000 -9310.175780000000 -2559.220950000000 7734.127440000000 4 39 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7778.261230000000 -1793.302370000000 0.000000000000 5000.000000000000 0.000000000000 -7778.261230000000 0.000000000000 5611.218260000000 0.000000000000 0.000000000000 5000.000000000000 1793.302370000000 -5611.218260000000 0.000000000000 0.000000000000 -7778.261230000000 1793.302370000000 13269.958000000001 -1967.901610000000 -8669.021479999999 7778.261230000000 0.000000000000 -5611.218260000000 -1967.901610000000 19164.197300000000 -2731.529050000000 -1793.302370000000 5611.218260000000 0.000000000000 -8669.021479999999 -2731.529050000000 7657.620610000000 4 40 55 4523.000000000000 0.000000000000 0.000000000000 0.000000000000 6936.350590000000 -2118.267580000000 0.000000000000 4523.000000000000 0.000000000000 -6936.350590000000 0.000000000000 5309.129390000000 0.000000000000 0.000000000000 4523.000000000000 2118.267580000000 -5309.129390000000 0.000000000000 0.000000000000 -6936.350590000000 2118.267580000000 12019.660200000000 -2456.807130000000 -8047.192380000000 6936.350590000000 0.000000000000 -5309.129390000000 -2456.807130000000 17475.800800000001 -3252.346190000000 -2118.267580000000 5309.129390000000 0.000000000000 -8047.192380000000 -3252.346190000000 7683.123540000000 4 41 55 4438.000000000000 0.000000000000 0.000000000000 0.000000000000 6652.313960000000 -2255.661380000000 0.000000000000 4438.000000000000 0.000000000000 -6652.313960000000 0.000000000000 4772.592290000000 0.000000000000 0.000000000000 4438.000000000000 2255.661380000000 -4772.592290000000 0.000000000000 0.000000000000 -6652.313960000000 2255.661380000000 11464.070299999999 -2396.675540000000 -7150.311040000000 6652.313960000000 0.000000000000 -4772.592290000000 -2396.675540000000 16041.703100000001 -3428.825200000000 -2255.661380000000 4772.592290000000 0.000000000000 -7150.311040000000 -3428.825200000000 7063.654300000000 4 43 55 3574.000000000000 0.000000000000 0.000000000000 0.000000000000 5858.933590000000 -1673.179080000000 0.000000000000 3574.000000000000 0.000000000000 -5858.933590000000 0.000000000000 309.703186000000 0.000000000000 0.000000000000 3574.000000000000 1673.179080000000 -309.703186000000 0.000000000000 0.000000000000 -5858.933590000000 1673.179080000000 10806.578100000001 71.287574800000 -220.256805000000 5858.933590000000 0.000000000000 -309.703186000000 71.287574800000 11258.111300000000 -2795.818360000000 -1673.179080000000 309.703186000000 0.000000000000 -220.256805000000 -2795.818360000000 2261.301760000000 4 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8690.151370000000 -1956.257080000000 0.000000000000 5000.000000000000 0.000000000000 -8690.151370000000 0.000000000000 -821.138916000000 0.000000000000 0.000000000000 5000.000000000000 1956.257080000000 821.138916000000 0.000000000000 0.000000000000 -8690.151370000000 1956.257080000000 16885.691400000000 727.356445000000 2146.070800000000 8690.151370000000 0.000000000000 821.138916000000 727.356445000000 17790.607400000001 -3640.387940000000 -1956.257080000000 -821.138916000000 0.000000000000 2146.070800000000 -3640.387940000000 3362.830320000000 4 45 55 3303.000000000000 0.000000000000 0.000000000000 0.000000000000 6396.884280000000 -1363.484740000000 0.000000000000 3303.000000000000 0.000000000000 -6396.884280000000 0.000000000000 -2266.934570000000 0.000000000000 0.000000000000 3303.000000000000 1363.484740000000 2266.934570000000 0.000000000000 0.000000000000 -6396.884280000000 1363.484740000000 13637.838900000001 1072.673710000000 4861.120610000000 6396.884280000000 0.000000000000 2266.934570000000 1072.673710000000 15157.398400000000 -2741.161380000000 -1363.484740000000 -2266.934570000000 0.000000000000 4861.120610000000 -2741.161380000000 3356.276610000000 5 36 55 3454.000000000000 0.000000000000 0.000000000000 0.000000000000 5769.393070000000 -702.225098000000 0.000000000000 3454.000000000000 0.000000000000 -5769.393070000000 0.000000000000 -788.885559000000 0.000000000000 0.000000000000 3454.000000000000 702.225098000000 788.885559000000 0.000000000000 0.000000000000 -5769.393070000000 702.225098000000 10347.247100000001 259.516449000000 1128.544190000000 5769.393070000000 0.000000000000 788.885559000000 259.516449000000 10449.501000000000 -1107.081300000000 -702.225098000000 -788.885559000000 0.000000000000 1128.544190000000 -1107.081300000000 900.312500000000 5 42 55 3360.000000000000 0.000000000000 0.000000000000 0.000000000000 4698.829100000000 -2028.276610000000 0.000000000000 3360.000000000000 0.000000000000 -4698.829100000000 0.000000000000 621.890503000000 0.000000000000 0.000000000000 3360.000000000000 2028.276610000000 -621.890503000000 0.000000000000 0.000000000000 -4698.829100000000 2028.276610000000 8094.980960000000 -483.958252000000 -801.638855000000 4698.829100000000 0.000000000000 -621.890503000000 -483.958252000000 7369.167970000000 -2863.559810000000 -2028.276610000000 621.890503000000 0.000000000000 -801.638855000000 -2863.559810000000 1813.119510000000 5 43 55 3244.000000000000 0.000000000000 0.000000000000 0.000000000000 4463.206050000000 -1211.818730000000 0.000000000000 3244.000000000000 0.000000000000 -4463.206050000000 0.000000000000 -897.737549000000 0.000000000000 0.000000000000 3244.000000000000 1211.818730000000 897.737549000000 0.000000000000 0.000000000000 -4463.206050000000 1211.818730000000 6981.453610000000 261.162903000000 1340.338010000000 4463.206050000000 0.000000000000 897.737549000000 261.162903000000 6869.051270000000 -1656.978640000000 -1211.818730000000 -897.737549000000 0.000000000000 1340.338010000000 -1656.978640000000 1074.437620000000 5 44 55 2118.000000000000 0.000000000000 0.000000000000 0.000000000000 2993.863530000000 -766.515930000000 0.000000000000 2118.000000000000 0.000000000000 -2993.863530000000 0.000000000000 -616.042603000000 0.000000000000 0.000000000000 2118.000000000000 766.515930000000 616.042603000000 0.000000000000 0.000000000000 -2993.863530000000 766.515930000000 4798.861820000000 165.875534000000 941.454346000000 2993.863530000000 0.000000000000 616.042603000000 165.875534000000 4735.256350000000 -1040.776980000000 -766.515930000000 -616.042603000000 0.000000000000 941.454346000000 -1040.776980000000 718.992615000000 6 36 55 3815.000000000000 0.000000000000 0.000000000000 0.000000000000 7889.995120000000 218.025192000000 0.000000000000 3815.000000000000 0.000000000000 -7889.995120000000 0.000000000000 -1842.578740000000 0.000000000000 0.000000000000 3815.000000000000 -218.025192000000 1842.578740000000 0.000000000000 0.000000000000 -7889.995120000000 -218.025192000000 16915.349600000001 -91.400001500000 3801.452150000000 7889.995120000000 0.000000000000 1842.578740000000 -91.400001500000 17627.101600000002 560.861450000000 218.025192000000 -1842.578740000000 0.000000000000 3801.452150000000 560.861450000000 1336.952760000000 6 42 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8328.783200000000 -1985.048950000000 0.000000000000 5000.000000000000 0.000000000000 -8328.783200000000 0.000000000000 -1435.530760000000 0.000000000000 0.000000000000 5000.000000000000 1985.048950000000 1435.530760000000 0.000000000000 0.000000000000 -8328.783200000000 1985.048950000000 15565.894500000000 445.962952000000 2583.945800000000 8328.783200000000 0.000000000000 1435.530760000000 445.962952000000 15671.445299999999 -3279.157710000000 -1985.048950000000 -1435.530760000000 0.000000000000 2583.945800000000 -3279.157710000000 1794.880740000000 6 43 55 4831.000000000000 0.000000000000 0.000000000000 0.000000000000 7709.826170000000 -1149.542480000000 0.000000000000 4831.000000000000 0.000000000000 -7709.826170000000 0.000000000000 -2636.166500000000 0.000000000000 0.000000000000 4831.000000000000 1149.542480000000 2636.166500000000 0.000000000000 0.000000000000 -7709.826170000000 1149.542480000000 13453.348599999999 393.168030000000 4625.142580000000 7709.826170000000 0.000000000000 2636.166500000000 393.168030000000 14813.653300000000 -1571.617680000000 -1149.542480000000 -2636.166500000000 0.000000000000 4625.142580000000 -1571.617680000000 2359.604740000000 6 44 55 3350.000000000000 0.000000000000 0.000000000000 0.000000000000 5895.125490000000 -533.495972000000 0.000000000000 3350.000000000000 0.000000000000 -5895.125490000000 0.000000000000 -2288.940190000000 0.000000000000 0.000000000000 3350.000000000000 533.495972000000 2288.940190000000 0.000000000000 0.000000000000 -5895.125490000000 533.495972000000 10937.767599999999 226.288406000000 4227.549320000000 5895.125490000000 0.000000000000 2288.940190000000 226.288406000000 12438.699199999999 -775.597168000000 -533.495972000000 -2288.940190000000 0.000000000000 4227.549320000000 -775.597168000000 2023.141240000000 7 36 55 2927.000000000000 0.000000000000 0.000000000000 0.000000000000 5765.692870000000 1466.255130000000 0.000000000000 2927.000000000000 0.000000000000 -5765.692870000000 0.000000000000 -2243.235840000000 0.000000000000 0.000000000000 2927.000000000000 -1466.255130000000 2243.235840000000 0.000000000000 0.000000000000 -5765.692870000000 -1466.255130000000 12606.726600000000 -1170.140260000000 4477.623540000000 5765.692870000000 0.000000000000 2243.235840000000 -1170.140260000000 13427.782200000000 3068.034910000000 1466.255130000000 -2243.235840000000 0.000000000000 4477.623540000000 3068.034910000000 2788.167720000000 7 42 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8480.438480000001 -317.317108000000 0.000000000000 5000.000000000000 0.000000000000 -8480.438480000001 0.000000000000 -2882.988040000000 0.000000000000 0.000000000000 5000.000000000000 317.317108000000 2882.988040000000 0.000000000000 0.000000000000 -8480.438480000001 317.317108000000 15462.409200000000 -45.908630400000 5032.027830000000 8480.438480000001 0.000000000000 2882.988040000000 -45.908630400000 17258.699199999999 -404.451599000000 -317.317108000000 -2882.988040000000 0.000000000000 5032.027830000000 -404.451599000000 2341.947510000000 7 43 55 2686.000000000000 0.000000000000 0.000000000000 0.000000000000 4066.960690000000 115.326584000000 0.000000000000 2686.000000000000 0.000000000000 -4066.960690000000 0.000000000000 -1928.404300000000 0.000000000000 0.000000000000 2686.000000000000 -115.326584000000 1928.404300000000 0.000000000000 0.000000000000 -4066.960690000000 -115.326584000000 6580.114750000000 -227.796616000000 3061.057620000000 4066.960690000000 0.000000000000 1928.404300000000 -227.796616000000 7961.963380000000 332.792694000000 115.326584000000 -1928.404300000000 0.000000000000 3061.057620000000 332.792694000000 1721.334840000000 8 10 55 1271.000000000000 0.000000000000 0.000000000000 0.000000000000 2270.154540000000 213.032379000000 0.000000000000 1271.000000000000 0.000000000000 -2270.154540000000 0.000000000000 -1119.507690000000 0.000000000000 0.000000000000 1271.000000000000 -213.032379000000 1119.507690000000 0.000000000000 0.000000000000 -2270.154540000000 -213.032379000000 4252.089360000000 -177.246490000000 2051.901610000000 2270.154540000000 0.000000000000 1119.507690000000 -177.246490000000 5186.446780000000 393.291779000000 213.032379000000 -1119.507690000000 0.000000000000 2051.901610000000 393.291779000000 1219.259030000000 8 18 55 2455.000000000000 0.000000000000 0.000000000000 0.000000000000 4782.434080000000 397.772827000000 0.000000000000 2455.000000000000 0.000000000000 -4782.434080000000 0.000000000000 -2757.036870000000 0.000000000000 0.000000000000 2455.000000000000 -397.772827000000 2757.036870000000 0.000000000000 0.000000000000 -4782.434080000000 -397.772827000000 9823.622069999999 -550.427063000000 5652.170900000000 4782.434080000000 0.000000000000 2757.036870000000 -550.427063000000 13060.285200000000 889.353455000000 397.772827000000 -2757.036870000000 0.000000000000 5652.170900000000 889.353455000000 3589.711430000000 8 20 55 3495.000000000000 0.000000000000 0.000000000000 0.000000000000 6501.740230000000 656.421631000000 0.000000000000 3495.000000000000 0.000000000000 -6501.740230000000 0.000000000000 -3481.895510000000 0.000000000000 0.000000000000 3495.000000000000 -656.421631000000 3481.895510000000 0.000000000000 0.000000000000 -6501.740230000000 -656.421631000000 12783.966800000000 -796.444641000000 6747.078130000000 6501.740230000000 0.000000000000 3481.895510000000 -796.444641000000 16270.061500000000 1367.619140000000 656.421631000000 -3481.895510000000 0.000000000000 6747.078130000000 1367.619140000000 4191.275390000000 8 36 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9868.768550000001 1376.554810000000 0.000000000000 5000.000000000000 0.000000000000 -9868.768550000001 0.000000000000 -4438.139160000000 0.000000000000 0.000000000000 5000.000000000000 -1376.554810000000 4438.139160000000 0.000000000000 0.000000000000 -9868.768550000001 -1376.554810000000 20764.107400000001 -1141.256590000000 9063.262699999999 9868.768550000001 0.000000000000 4438.139160000000 -1141.256590000000 25075.724600000001 2937.442630000000 1376.554810000000 -4438.139160000000 0.000000000000 9063.262699999999 2937.442630000000 5830.247560000000 8 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8837.012699999999 821.715271000000 0.000000000000 5000.000000000000 0.000000000000 -8837.012699999999 0.000000000000 -2570.722900000000 0.000000000000 0.000000000000 5000.000000000000 -821.715271000000 2570.722900000000 0.000000000000 0.000000000000 -8837.012699999999 -821.715271000000 16797.214800000002 -610.653625000000 4606.298830000000 8837.012699999999 0.000000000000 2570.722900000000 -610.653625000000 17804.986300000000 1802.752690000000 821.715271000000 -2570.722900000000 0.000000000000 4606.298830000000 1802.752690000000 2101.514400000000 8 44 55 3464.000000000000 0.000000000000 0.000000000000 0.000000000000 6299.442380000000 1028.779790000000 0.000000000000 3464.000000000000 0.000000000000 -6299.442380000000 0.000000000000 -2355.410640000000 0.000000000000 0.000000000000 3464.000000000000 -1028.779790000000 2355.410640000000 0.000000000000 0.000000000000 -6299.442380000000 -1028.779790000000 12213.839800000000 -763.419250000000 4350.190430000000 6299.442380000000 0.000000000000 2355.410640000000 -763.419250000000 13451.635700000001 2040.496220000000 1028.779790000000 -2355.410640000000 0.000000000000 4350.190430000000 2040.496220000000 2274.386230000000 9 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11316.812500000000 2173.463870000000 0.000000000000 5000.000000000000 0.000000000000 -11316.812500000000 0.000000000000 -3505.480470000000 0.000000000000 0.000000000000 5000.000000000000 -2173.463870000000 3505.480470000000 0.000000000000 0.000000000000 -11316.812500000000 -2173.463870000000 27756.671900000001 -1640.708010000000 8305.635740000000 11316.812500000000 0.000000000000 3505.480470000000 -1640.708010000000 29238.080099999999 4898.711430000000 2173.463870000000 -3505.480470000000 0.000000000000 8305.635740000000 4898.711430000000 4520.793950000000 9 19 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12976.669900000001 3320.607910000000 0.000000000000 5000.000000000000 0.000000000000 -12976.669900000001 0.000000000000 -5101.710450000000 0.000000000000 0.000000000000 5000.000000000000 -3320.607910000000 5101.710450000000 0.000000000000 0.000000000000 -12976.669900000001 -3320.607910000000 36541.238299999997 -3487.520020000000 13368.645500000001 12976.669900000001 0.000000000000 5101.710450000000 -3487.520020000000 39608.500000000000 8575.280269999999 3320.607910000000 -5101.710450000000 0.000000000000 13368.645500000001 8575.280269999999 8202.410159999999 9 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11285.217800000000 2602.795650000000 0.000000000000 5000.000000000000 0.000000000000 -11285.217800000000 0.000000000000 -3908.754390000000 0.000000000000 0.000000000000 5000.000000000000 -2602.795650000000 3908.754390000000 0.000000000000 0.000000000000 -11285.217800000000 -2602.795650000000 28481.941400000000 -2411.478270000000 9679.541020000001 11285.217800000000 0.000000000000 3908.754390000000 -2411.478270000000 30596.326200000000 6213.046880000000 2602.795650000000 -3908.754390000000 0.000000000000 9679.541020000001 6213.046880000000 6138.875980000000 9 37 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8754.100590000000 537.469055000000 0.000000000000 5000.000000000000 0.000000000000 -8754.100590000000 0.000000000000 1901.521240000000 0.000000000000 0.000000000000 5000.000000000000 -537.469055000000 -1901.521240000000 0.000000000000 0.000000000000 -8754.100590000000 -537.469055000000 16455.123000000000 97.194480900000 -3466.436040000000 8754.100590000000 0.000000000000 -1901.521240000000 97.194480900000 17186.455099999999 1114.144530000000 537.469055000000 1901.521240000000 0.000000000000 -3466.436040000000 1114.144530000000 2305.241940000000 9 38 55 4584.000000000000 0.000000000000 0.000000000000 0.000000000000 8315.701170000000 -393.532410000000 0.000000000000 4584.000000000000 0.000000000000 -8315.701170000000 0.000000000000 2574.723630000000 0.000000000000 0.000000000000 4584.000000000000 393.532410000000 -2574.723630000000 0.000000000000 0.000000000000 -8315.701170000000 393.532410000000 16146.920899999999 -163.920563000000 -4824.231930000000 8315.701170000000 0.000000000000 -2574.723630000000 -163.920563000000 17307.081999999999 -555.428894000000 -393.532410000000 2574.723630000000 0.000000000000 -4824.231930000000 -555.428894000000 2283.442870000000 9 39 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9017.631840000000 -708.621765000000 0.000000000000 5000.000000000000 0.000000000000 -9017.631840000000 0.000000000000 2580.377930000000 0.000000000000 0.000000000000 5000.000000000000 708.621765000000 -2580.377930000000 0.000000000000 0.000000000000 -9017.631840000000 708.621765000000 17313.302700000000 -473.353973000000 -4725.151370000000 9017.631840000000 0.000000000000 -2580.377930000000 -473.353973000000 18425.392599999999 -1106.679570000000 -708.621765000000 2580.377930000000 0.000000000000 -4725.151370000000 -1106.679570000000 2355.087890000000 9 40 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9032.511720000000 -943.165527000000 0.000000000000 5000.000000000000 0.000000000000 -9032.511720000000 0.000000000000 2415.021000000000 0.000000000000 0.000000000000 5000.000000000000 943.165527000000 -2415.021000000000 0.000000000000 0.000000000000 -9032.511720000000 943.165527000000 17541.355500000001 -540.973267000000 -4458.619630000000 9032.511720000000 0.000000000000 -2415.021000000000 -540.973267000000 18499.695299999999 -1429.967770000000 -943.165527000000 2415.021000000000 0.000000000000 -4458.619630000000 -1429.967770000000 2069.317140000000 9 41 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9251.782230000001 -1122.776490000000 0.000000000000 5000.000000000000 0.000000000000 -9251.782230000001 0.000000000000 2354.070310000000 0.000000000000 0.000000000000 5000.000000000000 1122.776490000000 -2354.070310000000 0.000000000000 0.000000000000 -9251.782230000001 1122.776490000000 18188.496100000000 -655.700439000000 -4488.166500000000 9251.782230000001 0.000000000000 -2354.070310000000 -655.700439000000 19260.337899999999 -1965.576660000000 -1122.776490000000 2354.070310000000 0.000000000000 -4488.166500000000 -1965.576660000000 2073.566410000000 9 42 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9010.706050000001 -1649.183110000000 0.000000000000 5000.000000000000 0.000000000000 -9010.706050000001 0.000000000000 -368.519012000000 0.000000000000 0.000000000000 5000.000000000000 1649.183110000000 368.519012000000 0.000000000000 0.000000000000 -9010.706050000001 1649.183110000000 17991.732400000001 293.747192000000 1445.948610000000 9010.706050000001 0.000000000000 368.519012000000 293.747192000000 19707.953099999999 -2965.682370000000 -1649.183110000000 -368.519012000000 0.000000000000 1445.948610000000 -2965.682370000000 3229.165040000000 10 11 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9791.104490000000 -880.255798000000 0.000000000000 5000.000000000000 0.000000000000 -9791.104490000000 0.000000000000 -5390.245610000000 0.000000000000 0.000000000000 5000.000000000000 880.255798000000 5390.245610000000 0.000000000000 0.000000000000 -9791.104490000000 880.255798000000 20790.041000000001 834.529358000000 10709.796899999999 9791.104490000000 0.000000000000 5390.245610000000 834.529358000000 26296.447300000000 -1106.463010000000 -880.255798000000 -5390.245610000000 0.000000000000 10709.796899999999 -1106.463010000000 6710.794430000000 10 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9651.066409999999 -1043.859860000000 0.000000000000 5000.000000000000 0.000000000000 -9651.066409999999 0.000000000000 -5176.811040000000 0.000000000000 0.000000000000 5000.000000000000 1043.859860000000 5176.811040000000 0.000000000000 0.000000000000 -9651.066409999999 1043.859860000000 20270.029299999998 1047.702150000000 10059.434600000001 9651.066409999999 0.000000000000 5176.811040000000 1047.702150000000 25384.988300000001 -1414.407710000000 -1043.859860000000 -5176.811040000000 0.000000000000 10059.434600000001 -1414.407710000000 6239.854000000000 10 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9568.626950000000 -1087.934450000000 0.000000000000 5000.000000000000 0.000000000000 -9568.626950000000 0.000000000000 -5118.036130000000 0.000000000000 0.000000000000 5000.000000000000 1087.934450000000 5118.036130000000 0.000000000000 0.000000000000 -9568.626950000000 1087.934450000000 19802.107400000001 979.192810000000 9990.420899999999 9568.626950000000 0.000000000000 5118.036130000000 979.192810000000 24873.404299999998 -1556.072750000000 -1087.934450000000 -5118.036130000000 0.000000000000 9990.420899999999 -1556.072750000000 6218.167970000000 10 53 55 4801.000000000000 0.000000000000 0.000000000000 0.000000000000 8501.691409999999 -1467.902470000000 0.000000000000 4801.000000000000 0.000000000000 -8501.691409999999 0.000000000000 -5211.820800000000 0.000000000000 0.000000000000 4801.000000000000 1467.902470000000 5211.820800000000 0.000000000000 0.000000000000 -8501.691409999999 1467.902470000000 16357.679700000001 1542.581910000000 9316.566409999999 8501.691409999999 0.000000000000 5211.820800000000 1542.581910000000 21707.623000000000 -2254.268550000000 -1467.902470000000 -5211.820800000000 0.000000000000 9316.566409999999 -2254.268550000000 6605.834470000000 11 18 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8327.430660000000 -1220.658450000000 0.000000000000 5000.000000000000 0.000000000000 -8327.430660000000 0.000000000000 1381.532710000000 0.000000000000 0.000000000000 5000.000000000000 1220.658450000000 -1381.532710000000 0.000000000000 0.000000000000 -8327.430660000000 1220.658450000000 14695.442400000000 -281.580078000000 -2468.580080000000 8327.430660000000 0.000000000000 -1381.532710000000 -281.580078000000 15243.846700000000 -1807.550900000000 -1220.658450000000 1381.532710000000 0.000000000000 -2468.580080000000 -1807.550900000000 1420.844730000000 11 19 55 1691.000000000000 0.000000000000 0.000000000000 0.000000000000 3893.410640000000 504.967346000000 0.000000000000 1691.000000000000 0.000000000000 -3893.410640000000 0.000000000000 1526.446170000000 0.000000000000 0.000000000000 1691.000000000000 -504.967346000000 -1526.446170000000 0.000000000000 0.000000000000 -3893.410640000000 -504.967346000000 9679.052729999999 493.451538000000 -3550.593260000000 3893.410640000000 0.000000000000 -1526.446170000000 493.451538000000 10633.964800000000 1408.302610000000 504.967346000000 1526.446170000000 0.000000000000 -3550.593260000000 1408.302610000000 1876.380490000000 11 20 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7594.001950000000 -1649.870730000000 0.000000000000 5000.000000000000 0.000000000000 -7594.001950000000 0.000000000000 1113.228030000000 0.000000000000 0.000000000000 5000.000000000000 1649.870730000000 -1113.228030000000 0.000000000000 0.000000000000 -7594.001950000000 1649.870730000000 12302.157200000000 -367.742584000000 -1774.443730000000 7594.001950000000 0.000000000000 -1113.228030000000 -367.742584000000 12461.825199999999 -2414.742190000000 -1649.870730000000 1113.228030000000 0.000000000000 -1774.443730000000 -2414.742190000000 1359.894170000000 11 21 55 3917.000000000000 0.000000000000 0.000000000000 0.000000000000 6538.811520000000 -832.649109000000 0.000000000000 3917.000000000000 0.000000000000 -6538.811520000000 0.000000000000 -369.547882000000 0.000000000000 0.000000000000 3917.000000000000 832.649109000000 369.547882000000 0.000000000000 0.000000000000 -6538.811520000000 832.649109000000 11354.490200000000 -44.452068300000 750.843567000000 6538.811520000000 0.000000000000 369.547882000000 -44.452068300000 11708.446300000000 -1275.956670000000 -832.649109000000 -369.547882000000 0.000000000000 750.843567000000 -1275.956670000000 880.132019000000 11 33 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12574.308600000000 -527.541382000000 0.000000000000 5000.000000000000 0.000000000000 -12574.308600000000 0.000000000000 -5493.597660000000 0.000000000000 0.000000000000 5000.000000000000 527.541382000000 5493.597660000000 0.000000000000 0.000000000000 -12574.308600000000 527.541382000000 34428.300799999997 562.695984000000 13879.076200000000 12574.308600000000 0.000000000000 5493.597660000000 562.695984000000 39368.746099999997 -213.533813000000 -527.541382000000 -5493.597660000000 0.000000000000 13879.076200000000 -213.533813000000 7500.506350000000 11 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9716.575199999999 -582.562256000000 0.000000000000 5000.000000000000 0.000000000000 -9716.575199999999 0.000000000000 2764.979250000000 0.000000000000 0.000000000000 5000.000000000000 582.562256000000 -2764.979250000000 0.000000000000 0.000000000000 -9716.575199999999 582.562256000000 19687.822300000000 -284.566254000000 -5446.639160000000 9716.575199999999 0.000000000000 -2764.979250000000 -284.566254000000 21214.486300000000 -824.815308000000 -582.562256000000 2764.979250000000 0.000000000000 -5446.639160000000 -824.815308000000 2012.521850000000 11 44 55 4159.000000000000 0.000000000000 0.000000000000 0.000000000000 8109.680180000000 -288.445038000000 0.000000000000 4159.000000000000 0.000000000000 -8109.680180000000 0.000000000000 2920.795170000000 0.000000000000 0.000000000000 4159.000000000000 288.445038000000 -2920.795170000000 0.000000000000 0.000000000000 -8109.680180000000 288.445038000000 16876.064500000000 73.047660800000 -6027.743650000000 8109.680180000000 0.000000000000 -2920.795170000000 73.047660800000 18795.552700000000 -116.612434000000 -288.445038000000 2920.795170000000 0.000000000000 -6027.743650000000 -116.612434000000 2816.318600000000 11 45 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10520.472700000000 390.527802000000 0.000000000000 5000.000000000000 0.000000000000 -10520.472700000000 0.000000000000 3046.491210000000 0.000000000000 0.000000000000 5000.000000000000 -390.527802000000 -3046.491210000000 0.000000000000 0.000000000000 -10520.472700000000 -390.527802000000 23778.511699999999 677.123657000000 -6840.669920000000 10520.472700000000 0.000000000000 -3046.491210000000 677.123657000000 25673.009800000000 1523.614260000000 390.527802000000 3046.491210000000 0.000000000000 -6840.669920000000 1523.614260000000 3324.358640000000 11 52 55 2550.000000000000 0.000000000000 0.000000000000 0.000000000000 4339.198240000000 -796.038269000000 0.000000000000 2550.000000000000 0.000000000000 -4339.198240000000 0.000000000000 -1703.005250000000 0.000000000000 0.000000000000 2550.000000000000 796.038269000000 1703.005250000000 0.000000000000 0.000000000000 -4339.198240000000 796.038269000000 7896.575680000000 508.734222000000 3006.414060000000 4339.198240000000 0.000000000000 1703.005250000000 508.734222000000 8789.516600000001 -1320.352660000000 -796.038269000000 -1703.005250000000 0.000000000000 3006.414060000000 -1320.352660000000 1691.559330000000 12 22 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9887.541020000001 -3284.637940000000 0.000000000000 5000.000000000000 0.000000000000 -9887.541020000001 0.000000000000 -4661.120610000000 0.000000000000 0.000000000000 5000.000000000000 3284.637940000000 4661.120610000000 0.000000000000 0.000000000000 -9887.541020000001 3284.637940000000 22068.293000000001 3155.619630000000 9446.300780000000 9887.541020000001 0.000000000000 4661.120610000000 3155.619630000000 24991.695299999999 -6476.898930000000 -3284.637940000000 -4661.120610000000 0.000000000000 9446.300780000000 -6476.898930000000 7371.234860000000 12 25 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13765.842800000000 -947.936401000000 0.000000000000 5000.000000000000 0.000000000000 -13765.842800000000 0.000000000000 -6122.646480000000 0.000000000000 0.000000000000 5000.000000000000 947.936401000000 6122.646480000000 0.000000000000 0.000000000000 -13765.842800000000 947.936401000000 39558.375000000000 1218.071660000000 16857.230500000001 13765.842800000000 0.000000000000 6122.646480000000 1218.071660000000 46592.578099999999 -1983.479130000000 -947.936401000000 -6122.646480000000 0.000000000000 16857.230500000001 -1983.479130000000 8286.756840000000 12 30 55 614.000000000000 0.000000000000 0.000000000000 0.000000000000 1754.823120000000 85.651756300000 0.000000000000 614.000000000000 0.000000000000 -1754.823120000000 0.000000000000 -453.068939000000 0.000000000000 0.000000000000 614.000000000000 -85.651756300000 453.068939000000 0.000000000000 0.000000000000 -1754.823120000000 -85.651756300000 5189.643550000000 -91.039321900000 1318.080570000000 1754.823120000000 0.000000000000 453.068939000000 -91.039321900000 5432.963870000000 284.634003000000 85.651756300000 -453.068939000000 0.000000000000 1318.080570000000 284.634003000000 473.565186000000 12 34 55 4582.000000000000 0.000000000000 0.000000000000 0.000000000000 8914.650390000001 -288.436127000000 0.000000000000 4582.000000000000 0.000000000000 -8914.650390000001 0.000000000000 1285.078610000000 0.000000000000 0.000000000000 4582.000000000000 288.436127000000 -1285.078610000000 0.000000000000 0.000000000000 -8914.650390000001 288.436127000000 18476.085899999998 -50.529529600000 -2412.077150000000 8914.650390000001 0.000000000000 -1285.078610000000 -50.529529600000 18505.328099999999 -484.055115000000 -288.436127000000 1285.078610000000 0.000000000000 -2412.077150000000 -484.055115000000 987.885925000000 12 46 55 2963.000000000000 0.000000000000 0.000000000000 0.000000000000 5194.740230000000 -926.228882000000 0.000000000000 2963.000000000000 0.000000000000 -5194.740230000000 0.000000000000 617.663086000000 0.000000000000 0.000000000000 2963.000000000000 926.228882000000 -617.663086000000 0.000000000000 0.000000000000 -5194.740230000000 926.228882000000 10501.772499999999 -242.939606000000 -948.909424000000 5194.740230000000 0.000000000000 -617.663086000000 -242.939606000000 10156.205099999999 -1570.118770000000 -926.228882000000 617.663086000000 0.000000000000 -948.909424000000 -1570.118770000000 758.056580000000 13 15 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11269.459999999999 -374.790222000000 0.000000000000 5000.000000000000 0.000000000000 -11269.459999999999 0.000000000000 -4929.934570000000 0.000000000000 0.000000000000 5000.000000000000 374.790222000000 4929.934570000000 0.000000000000 0.000000000000 -11269.459999999999 374.790222000000 26885.218799999999 413.579041000000 11036.285200000000 11269.459999999999 0.000000000000 4929.934570000000 413.579041000000 31042.877000000000 -435.626434000000 -374.790222000000 -4929.934570000000 0.000000000000 11036.285200000000 -435.626434000000 6623.421390000000 13 16 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10722.927700000000 -1764.593990000000 0.000000000000 5000.000000000000 0.000000000000 -10722.927700000000 0.000000000000 -4158.857910000000 0.000000000000 0.000000000000 5000.000000000000 1764.593990000000 4158.857910000000 0.000000000000 0.000000000000 -10722.927700000000 1764.593990000000 24458.625000000000 1319.798100000000 8978.570309999999 10722.927700000000 0.000000000000 4158.857910000000 1319.798100000000 27269.988300000001 -3507.187740000000 -1764.593990000000 -4158.857910000000 0.000000000000 8978.570309999999 -3507.187740000000 5329.183110000000 13 23 55 2220.000000000000 0.000000000000 0.000000000000 0.000000000000 4556.503910000000 -789.770203000000 0.000000000000 2220.000000000000 0.000000000000 -4556.503910000000 0.000000000000 -2516.307370000000 0.000000000000 0.000000000000 2220.000000000000 789.770203000000 2516.307370000000 0.000000000000 0.000000000000 -4556.503910000000 789.770203000000 10050.266600000001 955.747986000000 5129.918460000000 4556.503910000000 0.000000000000 2516.307370000000 955.747986000000 12420.094700000000 -1466.229250000000 -789.770203000000 -2516.307370000000 0.000000000000 5129.918460000000 -1466.229250000000 3585.418460000000 13 27 55 2681.000000000000 0.000000000000 0.000000000000 0.000000000000 7822.221190000000 2315.636720000000 0.000000000000 2681.000000000000 0.000000000000 -7822.221190000000 0.000000000000 -825.210266000000 0.000000000000 0.000000000000 2681.000000000000 -2315.636720000000 825.210266000000 0.000000000000 0.000000000000 -7822.221190000000 -2315.636720000000 25669.738300000001 -685.618347000000 1878.620000000000 7822.221190000000 0.000000000000 825.210266000000 -685.618347000000 24564.515599999999 6734.812500000000 2315.636720000000 -825.210266000000 0.000000000000 1878.620000000000 6734.812500000000 3728.378910000000 13 30 55 995.000000000000 0.000000000000 0.000000000000 0.000000000000 2841.270750000000 219.271484000000 0.000000000000 995.000000000000 0.000000000000 -2841.270750000000 0.000000000000 492.746490000000 0.000000000000 0.000000000000 995.000000000000 -219.271484000000 -492.746490000000 0.000000000000 0.000000000000 -2841.270750000000 -219.271484000000 8491.772460000000 118.126839000000 -1432.604370000000 2841.270750000000 0.000000000000 -492.746490000000 118.126839000000 8654.978520000001 677.623413000000 219.271484000000 492.746490000000 0.000000000000 -1432.604370000000 677.623413000000 344.753235000000 13 31 55 1954.000000000000 0.000000000000 0.000000000000 0.000000000000 3741.293460000000 -898.454285000000 0.000000000000 1954.000000000000 0.000000000000 -3741.293460000000 0.000000000000 210.780380000000 0.000000000000 0.000000000000 1954.000000000000 898.454285000000 -210.780380000000 0.000000000000 0.000000000000 -3741.293460000000 898.454285000000 7787.187010000000 -47.060985600000 -346.911591000000 3741.293460000000 0.000000000000 -210.780380000000 -47.060985600000 7380.084470000000 -1727.776730000000 -898.454285000000 210.780380000000 0.000000000000 -346.911591000000 -1727.776730000000 632.437012000000 13 33 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10689.691400000000 -1700.927250000000 0.000000000000 5000.000000000000 0.000000000000 -10689.691400000000 0.000000000000 458.447205000000 0.000000000000 0.000000000000 5000.000000000000 1700.927250000000 -458.447205000000 0.000000000000 0.000000000000 -10689.691400000000 1700.927250000000 24885.960899999998 -27.316799200000 -678.601990000000 10689.691400000000 0.000000000000 -458.447205000000 -27.316799200000 24550.656299999999 -3378.242190000000 -1700.927250000000 458.447205000000 0.000000000000 -678.601990000000 -3378.242190000000 1600.414790000000 13 47 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9148.968750000000 -1234.190430000000 0.000000000000 5000.000000000000 0.000000000000 -9148.968750000000 0.000000000000 720.310791000000 0.000000000000 0.000000000000 5000.000000000000 1234.190430000000 -720.310791000000 0.000000000000 0.000000000000 -9148.968750000000 1234.190430000000 18401.166000000001 595.615601000000 -1125.588990000000 9148.968750000000 0.000000000000 -720.310791000000 595.615601000000 18248.205099999999 -2424.029540000000 -1234.190430000000 720.310791000000 0.000000000000 -1125.588990000000 -2424.029540000000 2672.198970000000 13 51 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12075.760700000001 544.089844000000 0.000000000000 5000.000000000000 0.000000000000 -12075.760700000001 0.000000000000 -4941.559570000000 0.000000000000 0.000000000000 5000.000000000000 -544.089844000000 4941.559570000000 0.000000000000 0.000000000000 -12075.760700000001 -544.089844000000 30974.859400000001 -741.960938000000 12061.749000000000 12075.760700000001 0.000000000000 4941.559570000000 -741.960938000000 34851.851600000002 1888.762210000000 544.089844000000 -4941.559570000000 0.000000000000 12061.749000000000 1888.762210000000 6676.044430000000 14 22 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12205.199199999999 -2095.722170000000 0.000000000000 5000.000000000000 0.000000000000 -12205.199199999999 0.000000000000 -5679.387210000000 0.000000000000 0.000000000000 5000.000000000000 2095.722170000000 5679.387210000000 0.000000000000 0.000000000000 -12205.199199999999 2095.722170000000 31990.591799999998 2034.866210000000 14113.574199999999 12205.199199999999 0.000000000000 5679.387210000000 2034.866210000000 37190.894500000002 -4813.796880000000 -2095.722170000000 -5679.387210000000 0.000000000000 14113.574199999999 -4813.796880000000 8681.358399999999 14 27 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14633.049800000001 506.019287000000 0.000000000000 5000.000000000000 0.000000000000 -14633.049800000001 0.000000000000 5453.752440000000 0.000000000000 0.000000000000 5000.000000000000 -506.019287000000 -5453.752440000000 0.000000000000 0.000000000000 -14633.049800000001 -506.019287000000 44833.468800000002 513.846619000000 -16279.873000000000 14633.049800000001 0.000000000000 -5453.752440000000 513.846619000000 49660.339800000002 1738.702510000000 506.019287000000 5453.752440000000 0.000000000000 -16279.873000000000 1738.702510000000 7809.009770000000 14 28 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15670.711900000000 1374.184200000000 0.000000000000 5000.000000000000 0.000000000000 -15670.711900000000 0.000000000000 6084.118160000000 0.000000000000 0.000000000000 5000.000000000000 -1374.184200000000 -6084.118160000000 0.000000000000 0.000000000000 -15670.711900000000 -1374.184200000000 50964.507799999999 1596.111080000000 -19232.142599999999 15670.711900000000 0.000000000000 -6084.118160000000 1596.111080000000 57009.304700000001 4413.536130000000 1374.184200000000 6084.118160000000 0.000000000000 -19232.142599999999 4413.536130000000 9192.619140000001 14 48 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11243.595700000000 -2849.417480000000 0.000000000000 5000.000000000000 0.000000000000 -11243.595700000000 0.000000000000 -2106.107670000000 0.000000000000 0.000000000000 5000.000000000000 2849.417480000000 2106.107670000000 0.000000000000 0.000000000000 -11243.595700000000 2849.417480000000 27865.806600000000 1624.618770000000 4786.951170000000 11243.595700000000 0.000000000000 2106.107670000000 1624.618770000000 27811.314500000000 -6158.087400000000 -2849.417480000000 -2106.107670000000 0.000000000000 4786.951170000000 -6158.087400000000 4501.695800000000 14 50 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14816.376000000000 657.016541000000 0.000000000000 5000.000000000000 0.000000000000 -14816.376000000000 0.000000000000 -2186.783940000000 0.000000000000 0.000000000000 5000.000000000000 -657.016541000000 2186.783940000000 0.000000000000 0.000000000000 -14816.376000000000 -657.016541000000 45142.714800000002 99.761543300000 6628.229490000000 14816.376000000000 0.000000000000 2186.783940000000 99.761543300000 46070.027300000002 1826.809080000000 657.016541000000 -2186.783940000000 0.000000000000 6628.229490000000 1826.809080000000 2912.606450000000 14 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11207.625000000000 -2876.792240000000 0.000000000000 5000.000000000000 0.000000000000 -11207.625000000000 0.000000000000 -1353.924440000000 0.000000000000 0.000000000000 5000.000000000000 2876.792240000000 1353.924440000000 0.000000000000 0.000000000000 -11207.625000000000 2876.792240000000 27680.753900000000 1163.194820000000 3027.251460000000 11207.625000000000 0.000000000000 1353.924440000000 1163.194820000000 26486.953099999999 -6185.569820000000 -2876.792240000000 -1353.924440000000 0.000000000000 3027.251460000000 -6185.569820000000 3405.871340000000 15 17 55 1827.000000000000 0.000000000000 0.000000000000 0.000000000000 4167.994630000000 -486.925598000000 0.000000000000 1827.000000000000 0.000000000000 -4167.994630000000 0.000000000000 -2144.502440000000 0.000000000000 0.000000000000 1827.000000000000 486.925598000000 2144.502440000000 0.000000000000 0.000000000000 -4167.994630000000 486.925598000000 10187.994100000000 523.336670000000 4931.065430000000 4167.994630000000 0.000000000000 2144.502440000000 523.336670000000 12420.298800000000 -890.418274000000 -486.925598000000 -2144.502440000000 0.000000000000 4931.065430000000 -890.418274000000 3060.208010000000 15 26 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11594.594700000000 -217.630112000000 0.000000000000 5000.000000000000 0.000000000000 -11594.594700000000 0.000000000000 4892.209960000000 0.000000000000 0.000000000000 5000.000000000000 217.630112000000 -4892.209960000000 0.000000000000 0.000000000000 -11594.594700000000 217.630112000000 27889.396499999999 -75.720092800000 -11481.704100000001 11594.594700000000 0.000000000000 -4892.209960000000 -75.720092800000 32226.970700000002 -282.290527000000 -217.630112000000 4892.209960000000 0.000000000000 -11481.704100000001 -282.290527000000 5931.661620000000 15 48 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11545.410200000000 -2546.517820000000 0.000000000000 5000.000000000000 0.000000000000 -11545.410200000000 0.000000000000 -26.025394400000 0.000000000000 0.000000000000 5000.000000000000 2546.517820000000 26.025394400000 0.000000000000 0.000000000000 -11545.410200000000 2546.517820000000 29105.668000000001 273.098083000000 180.122910000000 11545.410200000000 0.000000000000 26.025394400000 273.098083000000 28557.445299999999 -5657.495120000000 -2546.517820000000 -26.025394400000 0.000000000000 180.122910000000 -5657.495120000000 3048.771000000000 15 50 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14280.232400000001 1489.732540000000 0.000000000000 5000.000000000000 0.000000000000 -14280.232400000001 0.000000000000 2194.121830000000 0.000000000000 0.000000000000 5000.000000000000 -1489.732540000000 -2194.121830000000 0.000000000000 0.000000000000 -14280.232400000001 -1489.732540000000 42275.800799999997 816.341309000000 -5971.149900000000 14280.232400000001 0.000000000000 -2194.121830000000 816.341309000000 43366.390599999999 4129.993160000000 1489.732540000000 2194.121830000000 0.000000000000 -5971.149900000000 4129.993160000000 3390.094970000000 15 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11598.392599999999 -2355.004150000000 0.000000000000 5000.000000000000 0.000000000000 -11598.392599999999 0.000000000000 758.351318000000 0.000000000000 0.000000000000 5000.000000000000 2355.004150000000 -758.351318000000 0.000000000000 0.000000000000 -11598.392599999999 2355.004150000000 28947.208999999999 92.459098800000 -1915.250000000000 11598.392599999999 0.000000000000 -758.351318000000 92.459098800000 28374.089800000002 -5361.142090000000 -2355.004150000000 758.351318000000 0.000000000000 -1915.250000000000 -5361.142090000000 2576.423580000000 16 21 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10691.869100000000 -2464.931880000000 0.000000000000 5000.000000000000 0.000000000000 -10691.869100000000 0.000000000000 -4473.770020000000 0.000000000000 0.000000000000 5000.000000000000 2464.931880000000 4473.770020000000 0.000000000000 0.000000000000 -10691.869100000000 2464.931880000000 25769.252000000000 1690.374150000000 10086.893599999999 10691.869100000000 0.000000000000 4473.770020000000 1690.374150000000 28487.857400000001 -4567.974120000000 -2464.931880000000 -4473.770020000000 0.000000000000 10086.893599999999 -4567.974120000000 6703.824220000000 16 25 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13060.939500000000 -1875.371340000000 0.000000000000 5000.000000000000 0.000000000000 -13060.939500000000 0.000000000000 3291.006590000000 0.000000000000 0.000000000000 5000.000000000000 1875.371340000000 -3291.006590000000 0.000000000000 0.000000000000 -13060.939500000000 1875.371340000000 36071.816400000003 -979.672546000000 -8628.205080000000 13060.939500000000 0.000000000000 -3291.006590000000 -979.672546000000 37674.117200000001 -4491.420410000000 -1875.371340000000 3291.006590000000 0.000000000000 -8628.205080000000 -4491.420410000000 3802.776120000000 16 47 55 2656.000000000000 0.000000000000 0.000000000000 0.000000000000 5481.596190000000 -1613.439090000000 0.000000000000 2656.000000000000 0.000000000000 -5481.596190000000 0.000000000000 -236.806915000000 0.000000000000 0.000000000000 2656.000000000000 1613.439090000000 236.806915000000 0.000000000000 0.000000000000 -5481.596190000000 1613.439090000000 12753.591800000000 -9.953729630000 363.826447000000 5481.596190000000 0.000000000000 236.806915000000 -9.953729630000 12383.981400000001 -3290.639160000000 -1613.439090000000 -236.806915000000 0.000000000000 363.826447000000 -3290.639160000000 1752.001100000000 16 50 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15289.670899999999 2670.702880000000 0.000000000000 5000.000000000000 0.000000000000 -15289.670899999999 0.000000000000 5426.718750000000 0.000000000000 0.000000000000 5000.000000000000 -2670.702880000000 -5426.718750000000 0.000000000000 0.000000000000 -15289.670899999999 -2670.702880000000 48964.664100000002 2823.692870000000 -16348.397499999999 15289.670899999999 0.000000000000 -5426.718750000000 2823.692870000000 53703.128900000003 8227.090819999999 2670.702880000000 5426.718750000000 0.000000000000 -16348.397499999999 8227.090819999999 8577.609380000000 16 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11857.209000000001 -2686.679690000000 0.000000000000 5000.000000000000 0.000000000000 -11857.209000000001 0.000000000000 2202.717290000000 0.000000000000 0.000000000000 5000.000000000000 2686.679690000000 -2202.717290000000 0.000000000000 0.000000000000 -11857.209000000001 2686.679690000000 30542.445299999999 -1133.620730000000 -5446.184080000000 11857.209000000001 0.000000000000 -2202.717290000000 -1133.620730000000 30529.144499999999 -6072.678710000000 -2686.679690000000 2202.717290000000 0.000000000000 -5446.184080000000 -6072.678710000000 3347.571780000000 17 18 55 2416.000000000000 0.000000000000 0.000000000000 0.000000000000 3804.579350000000 -826.489746000000 0.000000000000 2416.000000000000 0.000000000000 -3804.579350000000 0.000000000000 -2222.927490000000 0.000000000000 0.000000000000 2416.000000000000 826.489746000000 2222.927490000000 0.000000000000 0.000000000000 -3804.579350000000 826.489746000000 6968.376950000000 715.932190000000 3651.883790000000 3804.579350000000 0.000000000000 2222.927490000000 715.932190000000 8873.041990000000 -1215.640140000000 -826.489746000000 -2222.927490000000 0.000000000000 3651.883790000000 -1215.640140000000 2551.399170000000 17 23 55 2186.000000000000 0.000000000000 0.000000000000 0.000000000000 6939.848630000000 724.917175000000 0.000000000000 2186.000000000000 0.000000000000 -6939.848630000000 0.000000000000 1386.652470000000 0.000000000000 0.000000000000 2186.000000000000 -724.917175000000 -1386.652470000000 0.000000000000 0.000000000000 -6939.848630000000 -724.917175000000 22502.935500000000 512.964966000000 -4412.193360000000 6939.848630000000 0.000000000000 -1386.652470000000 512.964966000000 23164.882799999999 2372.527590000000 724.917175000000 1386.652470000000 0.000000000000 -4412.193360000000 2372.527590000000 1482.300900000000 17 34 55 3722.000000000000 0.000000000000 0.000000000000 0.000000000000 5604.704590000000 -1619.828370000000 0.000000000000 3722.000000000000 0.000000000000 -5604.704590000000 0.000000000000 -2045.555790000000 0.000000000000 0.000000000000 3722.000000000000 1619.828370000000 2045.555790000000 0.000000000000 0.000000000000 -5604.704590000000 1619.828370000000 9847.361330000000 698.366333000000 2922.112300000000 5604.704590000000 0.000000000000 2045.555790000000 698.366333000000 10921.733399999999 -2408.704100000000 -1619.828370000000 -2045.555790000000 0.000000000000 2922.112300000000 -2408.704100000000 2733.760990000000 17 47 55 4983.000000000000 0.000000000000 0.000000000000 0.000000000000 8337.694340000000 -2392.648930000000 0.000000000000 4983.000000000000 0.000000000000 -8337.694340000000 0.000000000000 692.162292000000 0.000000000000 0.000000000000 4983.000000000000 2392.648930000000 -692.162292000000 0.000000000000 0.000000000000 -8337.694340000000 2392.648930000000 16858.335899999998 -518.759827000000 -2386.989990000000 8337.694340000000 0.000000000000 -692.162292000000 -518.759827000000 17400.693400000000 -3920.062500000000 -2392.648930000000 692.162292000000 0.000000000000 -2386.989990000000 -3920.062500000000 3144.159420000000 17 53 55 3166.000000000000 0.000000000000 0.000000000000 0.000000000000 4386.361330000000 -1458.613160000000 0.000000000000 3166.000000000000 0.000000000000 -4386.361330000000 0.000000000000 -1390.099240000000 0.000000000000 0.000000000000 3166.000000000000 1458.613160000000 1390.099240000000 0.000000000000 0.000000000000 -4386.361330000000 1458.613160000000 7370.751950000000 582.244690000000 1837.088500000000 4386.361330000000 0.000000000000 1390.099240000000 582.244690000000 7632.625490000000 -2004.844970000000 -1458.613160000000 -1390.099240000000 0.000000000000 1837.088500000000 -2004.844970000000 1724.179440000000 18 21 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11406.121100000000 -935.358154000000 0.000000000000 5000.000000000000 0.000000000000 -11406.121100000000 0.000000000000 1345.770750000000 0.000000000000 0.000000000000 5000.000000000000 935.358154000000 -1345.770750000000 0.000000000000 0.000000000000 -11406.121100000000 935.358154000000 29447.197300000000 -271.313934000000 -3291.534180000000 11406.121100000000 0.000000000000 -1345.770750000000 -271.313934000000 29705.541000000001 -1327.819700000000 -935.358154000000 1345.770750000000 0.000000000000 -3291.534180000000 -1327.819700000000 1290.200070000000 18 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7994.011720000000 -1753.425660000000 0.000000000000 5000.000000000000 0.000000000000 -7994.011720000000 0.000000000000 -1479.351200000000 0.000000000000 0.000000000000 5000.000000000000 1753.425660000000 1479.351200000000 0.000000000000 0.000000000000 -7994.011720000000 1753.425660000000 13847.406300000001 467.051239000000 2138.384280000000 7994.011720000000 0.000000000000 1479.351200000000 467.051239000000 14926.751000000000 -2682.584720000000 -1753.425660000000 -1479.351200000000 0.000000000000 2138.384280000000 -2682.584720000000 2426.006840000000 18 35 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8050.366210000000 -1062.919800000000 0.000000000000 5000.000000000000 0.000000000000 -8050.366210000000 0.000000000000 -2957.656250000000 0.000000000000 0.000000000000 5000.000000000000 1062.919800000000 2957.656250000000 0.000000000000 0.000000000000 -8050.366210000000 1062.919800000000 13927.770500000001 110.720520000000 4265.788570000000 8050.366210000000 0.000000000000 2957.656250000000 110.720520000000 17792.677700000000 -1767.517580000000 -1062.919800000000 -2957.656250000000 0.000000000000 4265.788570000000 -1767.517580000000 4781.567870000000 18 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10155.910200000000 -981.856995000000 0.000000000000 5000.000000000000 0.000000000000 -10155.910200000000 0.000000000000 -2048.932130000000 0.000000000000 0.000000000000 5000.000000000000 981.856995000000 2048.932130000000 0.000000000000 0.000000000000 -10155.910200000000 981.856995000000 22723.910199999998 484.494293000000 3928.000240000000 10155.910200000000 0.000000000000 2048.932130000000 484.494293000000 24090.064500000000 -1360.968630000000 -981.856995000000 -2048.932130000000 0.000000000000 3928.000240000000 -1360.968630000000 2352.907470000000 18 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9529.810550000000 -615.600464000000 0.000000000000 5000.000000000000 0.000000000000 -9529.810550000000 0.000000000000 -3461.371830000000 0.000000000000 0.000000000000 5000.000000000000 615.600464000000 3461.371830000000 0.000000000000 0.000000000000 -9529.810550000000 615.600464000000 20672.611300000000 373.317444000000 5634.571290000000 9529.810550000000 0.000000000000 3461.371830000000 373.317444000000 24333.980500000001 -677.484314000000 -615.600464000000 -3461.371830000000 0.000000000000 5634.571290000000 -677.484314000000 4511.172850000000 18 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7878.499510000000 -1910.408810000000 0.000000000000 5000.000000000000 0.000000000000 -7878.499510000000 0.000000000000 -537.513794000000 0.000000000000 0.000000000000 5000.000000000000 1910.408810000000 537.513794000000 0.000000000000 0.000000000000 -7878.499510000000 1910.408810000000 13582.087900000000 149.869858000000 866.299133000000 7878.499510000000 0.000000000000 537.513794000000 149.869858000000 13673.460900000000 -2869.430420000000 -1910.408810000000 -537.513794000000 0.000000000000 866.299133000000 -2869.430420000000 1665.418950000000 18 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7632.002440000000 -1979.642090000000 0.000000000000 5000.000000000000 0.000000000000 -7632.002440000000 0.000000000000 -892.677979000000 0.000000000000 0.000000000000 5000.000000000000 1979.642090000000 892.677979000000 0.000000000000 0.000000000000 -7632.002440000000 1979.642090000000 12776.216800000000 307.500366000000 1334.551390000000 7632.002440000000 0.000000000000 892.677979000000 307.500366000000 13025.722700000000 -2914.762700000000 -1979.642090000000 -892.677979000000 0.000000000000 1334.551390000000 -2914.762700000000 1905.247800000000 18 54 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8163.469240000000 -1577.572140000000 0.000000000000 5000.000000000000 0.000000000000 -8163.469240000000 0.000000000000 -1422.544310000000 0.000000000000 0.000000000000 5000.000000000000 1577.572140000000 1422.544310000000 0.000000000000 0.000000000000 -8163.469240000000 1577.572140000000 14350.580099999999 254.739105000000 2058.141110000000 8163.469240000000 0.000000000000 1422.544310000000 254.739105000000 15626.136699999999 -2508.017580000000 -1577.572140000000 -1422.544310000000 0.000000000000 2058.141110000000 -2508.017580000000 2459.418700000000 19 35 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8555.333979999999 -151.967484000000 0.000000000000 5000.000000000000 0.000000000000 -8555.333979999999 0.000000000000 -493.321442000000 0.000000000000 0.000000000000 5000.000000000000 151.967484000000 493.321442000000 0.000000000000 0.000000000000 -8555.333979999999 151.967484000000 15878.255900000000 -134.114380000000 588.351440000000 8555.333979999999 0.000000000000 493.321442000000 -134.114380000000 15694.218800000001 -77.358169600000 -151.967484000000 -493.321442000000 0.000000000000 588.351440000000 -77.358169600000 1227.402830000000 19 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8858.767580000000 -1088.654910000000 0.000000000000 5000.000000000000 0.000000000000 -8858.767580000000 0.000000000000 -57.792144800000 0.000000000000 0.000000000000 5000.000000000000 1088.654910000000 57.792144800000 0.000000000000 0.000000000000 -8858.767580000000 1088.654910000000 16712.003900000000 -290.702606000000 -104.272606000000 8858.767580000000 0.000000000000 57.792144800000 -290.702606000000 16706.804700000001 -1994.006590000000 -1088.654910000000 -57.792144800000 0.000000000000 -104.272606000000 -1994.006590000000 1130.378540000000 19 45 55 3281.000000000000 0.000000000000 0.000000000000 0.000000000000 6000.416020000000 -882.233765000000 0.000000000000 3281.000000000000 0.000000000000 -6000.416020000000 0.000000000000 539.896362000000 0.000000000000 0.000000000000 3281.000000000000 882.233765000000 -539.896362000000 0.000000000000 0.000000000000 -6000.416020000000 882.233765000000 12312.771500000001 -345.838715000000 -1320.529660000000 6000.416020000000 0.000000000000 -539.896362000000 -345.838715000000 12556.911099999999 -1533.219120000000 -882.233765000000 539.896362000000 0.000000000000 -1320.529660000000 -1533.219120000000 1289.042720000000 19 54 55 2612.000000000000 0.000000000000 0.000000000000 0.000000000000 3994.774660000000 -793.433472000000 0.000000000000 2612.000000000000 0.000000000000 -3994.774660000000 0.000000000000 -87.680786100000 0.000000000000 0.000000000000 2612.000000000000 793.433472000000 87.680786100000 0.000000000000 0.000000000000 -3994.774660000000 793.433472000000 6690.168460000000 -190.802307000000 -17.554504400000 3994.774660000000 0.000000000000 87.680786100000 -190.802307000000 6773.930660000000 -1275.545040000000 -793.433472000000 -87.680786100000 0.000000000000 -17.554504400000 -1275.545040000000 928.379639000000 20 21 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12008.343800000001 -3321.381350000000 0.000000000000 5000.000000000000 0.000000000000 -12008.343800000001 0.000000000000 3099.879150000000 0.000000000000 0.000000000000 5000.000000000000 3321.381350000000 -3099.879150000000 0.000000000000 0.000000000000 -12008.343800000001 3321.381350000000 33750.613299999997 -2061.043700000000 -7724.699710000000 12008.343800000001 0.000000000000 -3099.879150000000 -2061.043700000000 33713.703099999999 -7844.667970000000 -3321.381350000000 3099.879150000000 0.000000000000 -7724.699710000000 -7844.667970000000 4662.025880000000 20 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7442.158690000000 -3606.758540000000 0.000000000000 5000.000000000000 0.000000000000 -7442.158690000000 0.000000000000 1271.360230000000 0.000000000000 0.000000000000 5000.000000000000 3606.758540000000 -1271.360230000000 0.000000000000 0.000000000000 -7442.158690000000 3606.758540000000 14003.540999999999 -979.842712000000 -1820.742800000000 7442.158690000000 0.000000000000 -1271.360230000000 -979.842712000000 12419.028300000000 -5317.822270000000 -3606.758540000000 1271.360230000000 0.000000000000 -1820.742800000000 -5317.822270000000 3646.476320000000 20 35 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7844.431150000000 -3583.032960000000 0.000000000000 5000.000000000000 0.000000000000 -7844.431150000000 0.000000000000 1494.873780000000 0.000000000000 0.000000000000 5000.000000000000 3583.032960000000 -1494.873780000000 0.000000000000 0.000000000000 -7844.431150000000 3583.032960000000 15339.670899999999 -1172.953130000000 -2044.001340000000 7844.431150000000 0.000000000000 -1494.873780000000 -1172.953130000000 14254.584999999999 -5546.560550000000 -3583.032960000000 1494.873780000000 0.000000000000 -2044.001340000000 -5546.560550000000 4087.771000000000 20 37 55 1427.000000000000 0.000000000000 0.000000000000 0.000000000000 4319.550780000000 -629.891113000000 0.000000000000 1427.000000000000 0.000000000000 -4319.550780000000 0.000000000000 623.916077000000 0.000000000000 0.000000000000 1427.000000000000 629.891113000000 -623.916077000000 0.000000000000 0.000000000000 -4319.550780000000 629.891113000000 13497.623000000000 -249.153854000000 -1831.379030000000 4319.550780000000 0.000000000000 -623.916077000000 -249.153854000000 13570.109399999999 -1927.240230000000 -629.891113000000 623.916077000000 0.000000000000 -1831.379030000000 -1927.240230000000 817.070251000000 20 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10418.248000000000 -2928.425290000000 0.000000000000 5000.000000000000 0.000000000000 -10418.248000000000 0.000000000000 131.329498000000 0.000000000000 0.000000000000 5000.000000000000 2928.425290000000 -131.329498000000 0.000000000000 0.000000000000 -10418.248000000000 2928.425290000000 25890.683600000000 8.239874840000 -708.352478000000 10418.248000000000 0.000000000000 -131.329498000000 8.239874840000 25006.087899999999 -5565.544920000000 -2928.425290000000 131.329498000000 0.000000000000 -708.352478000000 -5565.544920000000 2994.115480000000 20 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10793.011699999999 -2776.569580000000 0.000000000000 5000.000000000000 0.000000000000 -10793.011699999999 0.000000000000 141.622421000000 0.000000000000 0.000000000000 5000.000000000000 2776.569580000000 -141.622421000000 0.000000000000 0.000000000000 -10793.011699999999 2776.569580000000 27759.252000000000 15.635318800000 -719.048279000000 10793.011699999999 0.000000000000 -141.622421000000 15.635318800000 26872.953099999999 -5341.313960000000 -2776.569580000000 141.622421000000 0.000000000000 -719.048279000000 -5341.313960000000 2766.035400000000 20 45 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10739.160200000000 -2739.604000000000 0.000000000000 5000.000000000000 0.000000000000 -10739.160200000000 0.000000000000 379.217773000000 0.000000000000 0.000000000000 5000.000000000000 2739.604000000000 -379.217773000000 0.000000000000 0.000000000000 -10739.160200000000 2739.604000000000 27368.787100000001 -313.522186000000 -691.984802000000 10739.160200000000 0.000000000000 -379.217773000000 -313.522186000000 27020.275399999999 -5220.710940000000 -2739.604000000000 379.217773000000 0.000000000000 -691.984802000000 -5220.710940000000 3263.475340000000 20 46 55 4911.000000000000 0.000000000000 0.000000000000 0.000000000000 6969.529790000000 -3629.078860000000 0.000000000000 4911.000000000000 0.000000000000 -6969.529790000000 0.000000000000 1465.458980000000 0.000000000000 0.000000000000 4911.000000000000 3629.078860000000 -1465.458980000000 0.000000000000 0.000000000000 -6969.529790000000 3629.078860000000 12923.279300000000 -1166.406860000000 -1936.242310000000 6969.529790000000 0.000000000000 -1465.458980000000 -1166.406860000000 11385.211900000000 -5090.333980000000 -3629.078860000000 1465.458980000000 0.000000000000 -1936.242310000000 -5090.333980000000 3866.274900000000 20 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6887.918950000000 -3755.502930000000 0.000000000000 5000.000000000000 0.000000000000 -6887.918950000000 0.000000000000 1246.120360000000 0.000000000000 0.000000000000 5000.000000000000 3755.502930000000 -1246.120360000000 0.000000000000 0.000000000000 -6887.918950000000 3755.502930000000 12586.313500000000 -1066.047610000000 -1614.538450000000 6887.918950000000 0.000000000000 -1246.120360000000 -1066.047610000000 11013.413100000000 -5139.157230000000 -3755.502930000000 1246.120360000000 0.000000000000 -1614.538450000000 -5139.157230000000 4138.666020000000 20 54 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7513.332520000000 -3614.378660000000 0.000000000000 5000.000000000000 0.000000000000 -7513.332520000000 0.000000000000 1315.956300000000 0.000000000000 0.000000000000 5000.000000000000 3614.378660000000 -1315.956300000000 0.000000000000 0.000000000000 -7513.332520000000 3614.378660000000 14273.282200000000 -1023.406980000000 -1821.039550000000 7513.332520000000 0.000000000000 -1315.956300000000 -1023.406980000000 12715.521500000001 -5369.763670000000 -3614.378660000000 1315.956300000000 0.000000000000 -1821.039550000000 -5369.763670000000 3701.828860000000 21 34 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7446.021000000000 -1681.703610000000 0.000000000000 5000.000000000000 0.000000000000 -7446.021000000000 0.000000000000 -544.249329000000 0.000000000000 0.000000000000 5000.000000000000 1681.703610000000 544.249329000000 0.000000000000 0.000000000000 -7446.021000000000 1681.703610000000 12503.825199999999 -211.121918000000 777.429932000000 7446.021000000000 0.000000000000 544.249329000000 -211.121918000000 13054.885700000001 -2339.111080000000 -1681.703610000000 -544.249329000000 0.000000000000 777.429932000000 -2339.111080000000 2169.788570000000 21 35 55 3176.000000000000 0.000000000000 0.000000000000 0.000000000000 4649.851560000000 -864.827698000000 0.000000000000 3176.000000000000 0.000000000000 -4649.851560000000 0.000000000000 -858.706177000000 0.000000000000 0.000000000000 3176.000000000000 864.827698000000 858.706177000000 0.000000000000 0.000000000000 -4649.851560000000 864.827698000000 7418.081540000000 167.218933000000 1384.396480000000 4649.851560000000 0.000000000000 858.706177000000 167.218933000000 7641.668950000000 -1127.086790000000 -864.827698000000 -858.706177000000 0.000000000000 1384.396480000000 -1127.086790000000 821.279114000000 21 36 55 4520.000000000000 0.000000000000 0.000000000000 0.000000000000 11634.775400000000 1119.386600000000 0.000000000000 4520.000000000000 0.000000000000 -11634.775400000000 0.000000000000 -4149.062010000000 0.000000000000 0.000000000000 4520.000000000000 -1119.386600000000 4149.062010000000 0.000000000000 0.000000000000 -11634.775400000000 -1119.386600000000 31678.791000000001 -1174.683110000000 11048.362300000001 11634.775400000000 0.000000000000 4149.062010000000 -1174.683110000000 35310.074200000003 3327.904050000000 1119.386600000000 -4149.062010000000 0.000000000000 11048.362300000001 3327.904050000000 4806.314940000000 21 43 55 2053.000000000000 0.000000000000 0.000000000000 0.000000000000 3991.950680000000 -64.761970500000 0.000000000000 2053.000000000000 0.000000000000 -3991.950680000000 0.000000000000 -1534.729610000000 0.000000000000 0.000000000000 2053.000000000000 64.761970500000 1534.729610000000 0.000000000000 0.000000000000 -3991.950680000000 64.761970500000 8741.588870000000 -32.280593900000 3165.973390000000 3991.950680000000 0.000000000000 1534.729610000000 -32.280593900000 9803.299800000001 235.406708000000 -64.761970500000 -1534.729610000000 0.000000000000 3165.973390000000 235.406708000000 1446.861570000000 21 45 55 2866.000000000000 0.000000000000 0.000000000000 0.000000000000 4890.472170000000 -435.244781000000 0.000000000000 2866.000000000000 0.000000000000 -4890.472170000000 0.000000000000 -1557.183110000000 0.000000000000 0.000000000000 2866.000000000000 435.244781000000 1557.183110000000 0.000000000000 0.000000000000 -4890.472170000000 435.244781000000 9272.464840000001 137.544540000000 2847.006590000000 4890.472170000000 0.000000000000 1557.183110000000 137.544540000000 10066.669900000001 -409.837311000000 -435.244781000000 -1557.183110000000 0.000000000000 2847.006590000000 -409.837311000000 1246.613160000000 21 46 55 4756.000000000000 0.000000000000 0.000000000000 0.000000000000 6550.730470000000 -1695.957890000000 0.000000000000 4756.000000000000 0.000000000000 -6550.730470000000 0.000000000000 -500.257446000000 0.000000000000 0.000000000000 4756.000000000000 1695.957890000000 500.257446000000 0.000000000000 0.000000000000 -6550.730470000000 1695.957890000000 10189.158200000000 -32.988239300000 697.736328000000 6550.730470000000 0.000000000000 500.257446000000 -32.988239300000 10484.731400000001 -2209.503660000000 -1695.957890000000 -500.257446000000 0.000000000000 697.736328000000 -2209.503660000000 1759.999270000000 21 47 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7411.242680000000 -2658.716550000000 0.000000000000 5000.000000000000 0.000000000000 -7411.242680000000 0.000000000000 3273.717290000000 0.000000000000 0.000000000000 5000.000000000000 2658.716550000000 -3273.717290000000 0.000000000000 0.000000000000 -7411.242680000000 2658.716550000000 13645.068400000000 -1970.597660000000 -5595.175290000000 7411.242680000000 0.000000000000 -3273.717290000000 -1970.597660000000 15151.653300000000 -3830.907710000000 -2658.716550000000 3273.717290000000 0.000000000000 -5595.175290000000 -3830.907710000000 5092.042480000000 21 53 55 4343.000000000000 0.000000000000 0.000000000000 0.000000000000 6032.466310000000 -1662.042850000000 0.000000000000 4343.000000000000 0.000000000000 -6032.466310000000 0.000000000000 -273.701233000000 0.000000000000 0.000000000000 4343.000000000000 1662.042850000000 273.701233000000 0.000000000000 0.000000000000 -6032.466310000000 1662.042850000000 9583.877930000001 -190.487915000000 313.840271000000 6032.466310000000 0.000000000000 273.701233000000 -190.487915000000 9858.816409999999 -2242.855220000000 -1662.042850000000 -273.701233000000 0.000000000000 313.840271000000 -2242.855220000000 1878.942990000000 21 54 55 3708.000000000000 0.000000000000 0.000000000000 0.000000000000 5278.466800000000 -1095.532590000000 0.000000000000 3708.000000000000 0.000000000000 -5278.466800000000 0.000000000000 -823.969543000000 0.000000000000 0.000000000000 3708.000000000000 1095.532590000000 823.969543000000 0.000000000000 0.000000000000 -5278.466800000000 1095.532590000000 8274.749019999999 127.154243000000 1393.491700000000 5278.466800000000 0.000000000000 823.969543000000 127.154243000000 8518.950199999999 -1397.138310000000 -1095.532590000000 -823.969543000000 0.000000000000 1393.491700000000 -1397.138310000000 1042.700070000000 22 24 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14986.244100000000 3218.885740000000 0.000000000000 5000.000000000000 0.000000000000 -14986.244100000000 0.000000000000 5895.835450000000 0.000000000000 0.000000000000 5000.000000000000 -3218.885740000000 -5895.835450000000 0.000000000000 0.000000000000 -14986.244100000000 -3218.885740000000 49025.914100000002 3719.309330000000 -17586.105500000001 14986.244100000000 0.000000000000 -5895.835450000000 3719.309330000000 52803.707000000002 10226.019500000000 3218.885740000000 5895.835450000000 0.000000000000 -17586.105500000001 10226.019500000000 10538.082000000000 22 33 55 1065.000000000000 0.000000000000 0.000000000000 0.000000000000 1941.110720000000 -498.563965000000 0.000000000000 1065.000000000000 0.000000000000 -1941.110720000000 0.000000000000 882.604736000000 0.000000000000 0.000000000000 1065.000000000000 498.563965000000 -882.604736000000 0.000000000000 0.000000000000 -1941.110720000000 498.563965000000 3821.808350000000 -448.455139000000 -1594.953860000000 1941.110720000000 0.000000000000 -882.604736000000 -448.455139000000 4486.852050000000 -892.588135000000 -498.563965000000 882.604736000000 0.000000000000 -1594.953860000000 -892.588135000000 1203.051150000000 22 47 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9822.814450000000 -1980.586910000000 0.000000000000 5000.000000000000 0.000000000000 -9822.814450000000 0.000000000000 3347.993900000000 0.000000000000 0.000000000000 5000.000000000000 1980.586910000000 -3347.993900000000 0.000000000000 0.000000000000 -9822.814450000000 1980.586910000000 20873.076200000000 -1244.963500000000 -6793.039060000000 9822.814450000000 0.000000000000 -3347.993900000000 -1244.963500000000 22829.019499999999 -3550.176270000000 -1980.586910000000 3347.993900000000 0.000000000000 -6793.039060000000 -3550.176270000000 4140.287110000000 22 48 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11485.798800000000 -693.519165000000 0.000000000000 5000.000000000000 0.000000000000 -11485.798800000000 0.000000000000 4460.766600000000 0.000000000000 0.000000000000 5000.000000000000 693.519165000000 -4460.766600000000 0.000000000000 0.000000000000 -11485.798800000000 693.519165000000 28869.837899999999 -279.761108000000 -10715.751000000000 11485.798800000000 0.000000000000 -4460.766600000000 -279.761108000000 32473.925800000001 -485.584961000000 -693.519165000000 4460.766600000000 0.000000000000 -10715.751000000000 -485.584961000000 5787.222170000000 22 49 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13223.796899999999 1306.123540000000 0.000000000000 5000.000000000000 0.000000000000 -13223.796899999999 0.000000000000 5843.627930000000 0.000000000000 0.000000000000 5000.000000000000 -1306.123540000000 -5843.627930000000 0.000000000000 0.000000000000 -13223.796899999999 -1306.123540000000 37493.210899999998 1107.034910000000 -15218.203100000001 13223.796899999999 0.000000000000 -5843.627930000000 1107.034910000000 42926.585899999998 4344.255370000000 1306.123540000000 5843.627930000000 0.000000000000 -15218.203100000001 4344.255370000000 8944.692380000000 22 51 55 3973.000000000000 0.000000000000 0.000000000000 0.000000000000 10513.783200000000 1517.938600000000 0.000000000000 3973.000000000000 0.000000000000 -10513.783200000000 0.000000000000 4575.649900000000 0.000000000000 0.000000000000 3973.000000000000 -1517.938600000000 -4575.649900000000 0.000000000000 0.000000000000 -10513.783200000000 -1517.938600000000 31004.466799999998 1352.036250000000 -11912.863300000001 10513.783200000000 0.000000000000 -4575.649900000000 1352.036250000000 34367.707000000002 5120.174800000000 1517.938600000000 4575.649900000000 0.000000000000 -11912.863300000001 5120.174800000000 7907.705080000000 22 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10736.834999999999 -1269.552610000000 0.000000000000 5000.000000000000 0.000000000000 -10736.834999999999 0.000000000000 4794.533690000000 0.000000000000 0.000000000000 5000.000000000000 1269.552610000000 -4794.533690000000 0.000000000000 0.000000000000 -10736.834999999999 1269.552610000000 24505.527300000002 -959.832031000000 -10734.395500000001 10736.834999999999 0.000000000000 -4794.533690000000 -959.832031000000 29194.554700000001 -2221.264650000000 -1269.552610000000 4794.533690000000 0.000000000000 -10734.395500000001 -2221.264650000000 6127.811040000000 23 25 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12442.965800000000 -1844.444460000000 0.000000000000 5000.000000000000 0.000000000000 -12442.965800000000 0.000000000000 2859.942870000000 0.000000000000 0.000000000000 5000.000000000000 1844.444460000000 -2859.942870000000 0.000000000000 0.000000000000 -12442.965800000000 1844.444460000000 33158.070299999999 -869.399292000000 -7126.307130000000 12442.965800000000 0.000000000000 -2859.942870000000 -869.399292000000 34250.550799999997 -4254.927730000000 -1844.444460000000 2859.942870000000 0.000000000000 -7126.307130000000 -4254.927730000000 2936.264650000000 23 48 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10611.570299999999 -2451.791750000000 0.000000000000 5000.000000000000 0.000000000000 -10611.570299999999 0.000000000000 1914.117070000000 0.000000000000 0.000000000000 5000.000000000000 2451.791750000000 -1914.117070000000 0.000000000000 0.000000000000 -10611.570299999999 2451.791750000000 24551.531299999999 -982.082458000000 -3874.573490000000 10611.570299999999 0.000000000000 -1914.117070000000 -982.082458000000 24799.886699999999 -5046.464360000000 -2451.791750000000 1914.117070000000 0.000000000000 -3874.573490000000 -5046.464360000000 3210.125980000000 23 50 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13807.796899999999 2135.104490000000 0.000000000000 5000.000000000000 0.000000000000 -13807.796899999999 0.000000000000 2575.516110000000 0.000000000000 0.000000000000 5000.000000000000 -2135.104490000000 -2575.516110000000 0.000000000000 0.000000000000 -13807.796899999999 -2135.104490000000 40872.757799999999 627.683289000000 -6859.031740000000 13807.796899999999 0.000000000000 -2575.516110000000 627.683289000000 42137.980499999998 5774.519530000000 2135.104490000000 2575.516110000000 0.000000000000 -6859.031740000000 5774.519530000000 5912.800290000000 24 26 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10064.393599999999 -1660.502440000000 0.000000000000 5000.000000000000 0.000000000000 -10064.393599999999 0.000000000000 4846.410160000000 0.000000000000 0.000000000000 5000.000000000000 1660.502440000000 -4846.410160000000 0.000000000000 0.000000000000 -10064.393599999999 1660.502440000000 21953.560500000000 -1727.127930000000 -9860.775390000001 10064.393599999999 0.000000000000 -4846.410160000000 -1727.127930000000 25772.250000000000 -3124.010740000000 -1660.502440000000 4846.410160000000 0.000000000000 -9860.775390000001 -3124.010740000000 6491.325200000000 24 48 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8491.658200000000 -3880.572270000000 0.000000000000 5000.000000000000 0.000000000000 -8491.658200000000 0.000000000000 596.399414000000 0.000000000000 0.000000000000 5000.000000000000 3880.572270000000 -596.399414000000 0.000000000000 0.000000000000 -8491.658200000000 3880.572270000000 18338.843799999999 -263.889069000000 -719.938171000000 8491.658200000000 0.000000000000 -596.399414000000 -263.889069000000 16091.083000000001 -6372.294430000000 -3880.572270000000 596.399414000000 0.000000000000 -719.938171000000 -6372.294430000000 4825.374510000000 24 50 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12553.727500000001 -113.408073000000 0.000000000000 5000.000000000000 0.000000000000 -12553.727500000001 0.000000000000 68.329086300000 0.000000000000 0.000000000000 5000.000000000000 113.408073000000 -68.329086300000 0.000000000000 0.000000000000 -12553.727500000001 113.408073000000 32855.589800000002 297.077332000000 158.194946000000 12553.727500000001 0.000000000000 -68.329086300000 297.077332000000 33266.773399999998 -439.899689000000 -113.408073000000 68.329086300000 0.000000000000 158.194946000000 -439.899689000000 2164.217040000000 24 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8203.812500000000 -4170.208980000000 0.000000000000 5000.000000000000 0.000000000000 -8203.812500000000 0.000000000000 1257.563960000000 0.000000000000 0.000000000000 5000.000000000000 4170.208980000000 -1257.563960000000 0.000000000000 0.000000000000 -8203.812500000000 4170.208980000000 17830.156299999999 -949.557983000000 -1814.114750000000 8203.812500000000 0.000000000000 -1257.563960000000 -949.557983000000 14995.522499999999 -6556.531740000000 -4170.208980000000 1257.563960000000 0.000000000000 -1814.114750000000 -6556.531740000000 5072.565430000000 25 27 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13213.421899999999 4458.151370000000 0.000000000000 5000.000000000000 0.000000000000 -13213.421899999999 0.000000000000 5495.126950000000 0.000000000000 0.000000000000 5000.000000000000 -4458.151370000000 -5495.126950000000 0.000000000000 0.000000000000 -13213.421899999999 -4458.151370000000 39390.808599999997 4807.625980000000 -14517.752000000000 13213.421899999999 0.000000000000 -5495.126950000000 4807.625980000000 41762.875000000000 12005.450199999999 4458.151370000000 5495.126950000000 0.000000000000 -14517.752000000000 12005.450199999999 10832.877899999999 25 28 55 3803.000000000000 0.000000000000 0.000000000000 0.000000000000 10370.553700000000 3737.670170000000 0.000000000000 3803.000000000000 0.000000000000 -10370.553700000000 0.000000000000 4148.078610000000 0.000000000000 0.000000000000 3803.000000000000 -3737.670170000000 -4148.078610000000 0.000000000000 0.000000000000 -10370.553700000000 -3737.670170000000 32123.494100000000 4042.906740000000 -11328.265600000001 10370.553700000000 0.000000000000 -4148.078610000000 4042.906740000000 33278.546900000001 10264.805700000001 3737.670170000000 4148.078610000000 0.000000000000 -11328.265600000001 10264.805700000001 8671.354490000000 25 31 55 584.000000000000 0.000000000000 0.000000000000 0.000000000000 746.326843000000 -237.517776000000 0.000000000000 584.000000000000 0.000000000000 -746.326843000000 0.000000000000 307.521179000000 0.000000000000 0.000000000000 584.000000000000 237.517776000000 -307.521179000000 0.000000000000 0.000000000000 -746.326843000000 237.517776000000 1089.448360000000 -119.071884000000 -398.680481000000 746.326843000000 0.000000000000 -307.521179000000 -119.071884000000 1160.911620000000 -309.273163000000 -237.517776000000 307.521179000000 0.000000000000 -398.680481000000 -309.273163000000 284.057831000000 25 32 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8918.324220000000 -575.602417000000 0.000000000000 5000.000000000000 0.000000000000 -8918.324220000000 0.000000000000 3243.855220000000 0.000000000000 0.000000000000 5000.000000000000 575.602417000000 -3243.855220000000 0.000000000000 0.000000000000 -8918.324220000000 575.602417000000 16637.502000000000 45.400001500000 -6108.779300000000 8918.324220000000 0.000000000000 -3243.855220000000 45.400001500000 19481.474600000001 -741.350647000000 -575.602417000000 3243.855220000000 0.000000000000 -6108.779300000000 -741.350647000000 3721.063720000000 25 33 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8225.539059999999 -1215.638060000000 0.000000000000 5000.000000000000 0.000000000000 -8225.539059999999 0.000000000000 3340.327150000000 0.000000000000 0.000000000000 5000.000000000000 1215.638060000000 -3340.327150000000 0.000000000000 0.000000000000 -8225.539059999999 1215.638060000000 14237.473599999999 -679.453796000000 -5601.042480000000 8225.539059999999 0.000000000000 -3340.327150000000 -679.453796000000 16626.179700000001 -1865.639890000000 -1215.638060000000 3340.327150000000 0.000000000000 -5601.042480000000 -1865.639890000000 3328.948240000000 25 47 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7399.253420000000 -2004.826900000000 0.000000000000 5000.000000000000 0.000000000000 -7399.253420000000 0.000000000000 1460.710940000000 0.000000000000 0.000000000000 5000.000000000000 2004.826900000000 -1460.710940000000 0.000000000000 0.000000000000 -7399.253420000000 2004.826900000000 12187.411099999999 -381.774261000000 -2071.055420000000 7399.253420000000 0.000000000000 -1460.710940000000 -381.774261000000 12614.422900000000 -2934.325440000000 -2004.826900000000 1460.710940000000 0.000000000000 -2071.055420000000 -2934.325440000000 2241.707280000000 25 50 55 4184.000000000000 0.000000000000 0.000000000000 0.000000000000 9874.644530000000 2581.521970000000 0.000000000000 4184.000000000000 0.000000000000 -9874.644530000000 0.000000000000 -3140.971440000000 0.000000000000 0.000000000000 4184.000000000000 -2581.521970000000 3140.971440000000 0.000000000000 0.000000000000 -9874.644530000000 -2581.521970000000 25251.273399999998 -1713.574830000000 7557.761230000000 9874.644530000000 0.000000000000 3140.971440000000 -1713.574830000000 26197.556600000000 6018.210940000000 2581.521970000000 -3140.971440000000 0.000000000000 7557.761230000000 6018.210940000000 4584.023930000000 26 29 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13926.385700000001 1891.432010000000 0.000000000000 5000.000000000000 0.000000000000 -13926.385700000001 0.000000000000 4019.864500000000 0.000000000000 0.000000000000 5000.000000000000 -1891.432010000000 -4019.864500000000 0.000000000000 0.000000000000 -13926.385700000001 -1891.432010000000 40490.027300000002 1336.487920000000 -10980.341800000000 13926.385700000001 0.000000000000 -4019.864500000000 1336.487920000000 42747.484400000001 5463.808590000000 1891.432010000000 4019.864500000000 0.000000000000 -10980.341800000000 5463.808590000000 4847.381350000000 26 49 55 3878.000000000000 0.000000000000 0.000000000000 0.000000000000 6822.473630000000 -616.273743000000 0.000000000000 3878.000000000000 0.000000000000 -6822.473630000000 0.000000000000 -2437.169430000000 0.000000000000 0.000000000000 3878.000000000000 616.273743000000 2437.169430000000 0.000000000000 0.000000000000 -6822.473630000000 616.273743000000 12539.410200000000 227.105087000000 4301.887700000000 6822.473630000000 0.000000000000 2437.169430000000 227.105087000000 14056.499000000000 -1142.835820000000 -616.273743000000 -2437.169430000000 0.000000000000 4301.887700000000 -1142.835820000000 2420.192630000000 29 30 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9502.671880000000 -2337.795650000000 0.000000000000 5000.000000000000 0.000000000000 -9502.671880000000 0.000000000000 4244.478520000000 0.000000000000 0.000000000000 5000.000000000000 2337.795650000000 -4244.478520000000 0.000000000000 0.000000000000 -9502.671880000000 2337.795650000000 20496.611300000000 -1661.322270000000 -8528.679690000001 9502.671880000000 0.000000000000 -4244.478520000000 -1661.322270000000 23291.777300000002 -3835.428470000000 -2337.795650000000 4244.478520000000 0.000000000000 -8528.679690000001 -3835.428470000000 5760.000980000000 30 31 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6439.758790000000 -1437.178340000000 0.000000000000 5000.000000000000 0.000000000000 -6439.758790000000 0.000000000000 3287.651120000000 0.000000000000 0.000000000000 5000.000000000000 1437.178340000000 -3287.651120000000 0.000000000000 0.000000000000 -6439.758790000000 1437.178340000000 9184.176760000000 -867.910645000000 -4183.128910000000 6439.758790000000 0.000000000000 -3287.651120000000 -867.910645000000 10775.647499999999 -1995.600950000000 -1437.178340000000 3287.651120000000 0.000000000000 -4183.128910000000 -1995.600950000000 3142.495850000000 30 32 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7903.414060000000 -1645.789920000000 0.000000000000 5000.000000000000 0.000000000000 -7903.414060000000 0.000000000000 -949.175903000000 0.000000000000 0.000000000000 5000.000000000000 1645.789920000000 949.175903000000 0.000000000000 0.000000000000 -7903.414060000000 1645.789920000000 13613.944299999999 279.745239000000 2140.337650000000 7903.414060000000 0.000000000000 949.175903000000 279.745239000000 14512.967800000000 -2588.693850000000 -1645.789920000000 -949.175903000000 0.000000000000 2140.337650000000 -2588.693850000000 2293.541020000000 30 33 55 4297.000000000000 0.000000000000 0.000000000000 0.000000000000 5401.181150000000 -742.177856000000 0.000000000000 4297.000000000000 0.000000000000 -5401.181150000000 0.000000000000 2672.743410000000 0.000000000000 0.000000000000 4297.000000000000 742.177856000000 -2672.743410000000 0.000000000000 0.000000000000 -5401.181150000000 742.177856000000 7387.204590000000 -305.355011000000 -3219.210940000000 5401.181150000000 0.000000000000 -2672.743410000000 -305.355011000000 8918.832030000000 -1120.917480000000 -742.177856000000 2672.743410000000 0.000000000000 -3219.210940000000 -1120.917480000000 2372.396240000000 30 48 55 1108.000000000000 0.000000000000 0.000000000000 0.000000000000 1337.256470000000 -433.851105000000 0.000000000000 1108.000000000000 0.000000000000 -1337.256470000000 0.000000000000 1078.225460000000 0.000000000000 0.000000000000 1108.000000000000 433.851105000000 -1078.225460000000 0.000000000000 0.000000000000 -1337.256470000000 433.851105000000 1903.349980000000 -422.775909000000 -1297.416990000000 1337.256470000000 0.000000000000 -1078.225460000000 -422.775909000000 2718.419920000000 -549.475647000000 -433.851105000000 1078.225460000000 0.000000000000 -1297.416990000000 -549.475647000000 1318.466190000000 31 34 55 1687.000000000000 0.000000000000 0.000000000000 0.000000000000 2749.701170000000 -150.779709000000 0.000000000000 1687.000000000000 0.000000000000 -2749.701170000000 0.000000000000 1393.214360000000 0.000000000000 0.000000000000 1687.000000000000 150.779709000000 -1393.214360000000 0.000000000000 0.000000000000 -2749.701170000000 150.779709000000 4602.060060000000 -121.026535000000 -2277.989010000000 2749.701170000000 0.000000000000 -1393.214360000000 -121.026535000000 5681.375490000000 -218.319366000000 -150.779709000000 1393.214360000000 0.000000000000 -2277.989010000000 -218.319366000000 1248.006590000000 31 53 55 4242.000000000000 0.000000000000 0.000000000000 0.000000000000 6365.977050000000 -49.464550000000 0.000000000000 4242.000000000000 0.000000000000 -6365.977050000000 0.000000000000 2869.774410000000 0.000000000000 0.000000000000 4242.000000000000 49.464550000000 -2869.774410000000 0.000000000000 0.000000000000 -6365.977050000000 49.464550000000 10031.214800000000 -107.370300000000 -4440.607420000000 6365.977050000000 0.000000000000 -2869.774410000000 -107.370300000000 11877.905300000000 -106.069069000000 -49.464550000000 2869.774410000000 0.000000000000 -4440.607420000000 -106.069069000000 2383.714110000000 32 34 55 2365.000000000000 0.000000000000 0.000000000000 0.000000000000 4151.656740000000 -142.208633000000 0.000000000000 2365.000000000000 0.000000000000 -4151.656740000000 0.000000000000 2130.397220000000 0.000000000000 0.000000000000 2365.000000000000 142.208633000000 -2130.397220000000 0.000000000000 0.000000000000 -4151.656740000000 142.208633000000 7451.578610000000 -96.002677900000 -3766.499020000000 4151.656740000000 0.000000000000 -2130.397220000000 -96.002677900000 9307.371090000001 -198.880341000000 -142.208633000000 2130.397220000000 0.000000000000 -3766.499020000000 -198.880341000000 2075.741700000000 32 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8649.255859999999 140.706741000000 0.000000000000 5000.000000000000 0.000000000000 -8649.255859999999 0.000000000000 3669.845210000000 0.000000000000 0.000000000000 5000.000000000000 -140.706741000000 -3669.845210000000 0.000000000000 0.000000000000 -8649.255859999999 -140.706741000000 15488.342800000000 82.747398400000 -6432.446780000000 8649.255859999999 0.000000000000 -3669.845210000000 82.747398400000 18097.193400000000 292.306580000000 140.706741000000 3669.845210000000 0.000000000000 -6432.446780000000 292.306580000000 3404.245360000000 33 35 55 3396.000000000000 0.000000000000 0.000000000000 0.000000000000 9949.536130000000 1665.875980000000 0.000000000000 3396.000000000000 0.000000000000 -9949.536130000000 0.000000000000 4243.941410000000 0.000000000000 0.000000000000 3396.000000000000 -1665.875980000000 -4243.941410000000 0.000000000000 0.000000000000 -9949.536130000000 -1665.875980000000 30520.627000000000 2095.675290000000 -12440.841800000000 9949.536130000000 0.000000000000 -4243.941410000000 2095.675290000000 34931.820299999999 4970.252930000000 1665.875980000000 4243.941410000000 0.000000000000 -12440.841800000000 4970.252930000000 6308.406250000000 33 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10098.816400000000 -990.812927000000 0.000000000000 5000.000000000000 0.000000000000 -10098.816400000000 0.000000000000 4114.985840000000 0.000000000000 0.000000000000 5000.000000000000 990.812927000000 -4114.985840000000 0.000000000000 0.000000000000 -10098.816400000000 990.812927000000 21725.992200000001 -1028.237430000000 -7999.646480000000 10098.816400000000 0.000000000000 -4114.985840000000 -1028.237430000000 24702.781299999999 -1585.347050000000 -990.812927000000 4114.985840000000 0.000000000000 -7999.646480000000 -1585.347050000000 4550.222170000000 34 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12145.523400000000 2295.590090000000 0.000000000000 5000.000000000000 0.000000000000 -12145.523400000000 0.000000000000 5758.431150000000 0.000000000000 0.000000000000 5000.000000000000 -2295.590090000000 -5758.431150000000 0.000000000000 0.000000000000 -12145.523400000000 -2295.590090000000 32227.197300000000 2488.437010000000 -13758.840800000000 12145.523400000000 0.000000000000 -5758.431150000000 2488.437010000000 37339.578099999999 6312.460940000000 2295.590090000000 5758.431150000000 0.000000000000 -13758.840800000000 6312.460940000000 8768.000000000000 34 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13009.665000000001 3307.643800000000 0.000000000000 5000.000000000000 0.000000000000 -13009.665000000001 0.000000000000 5953.102050000000 0.000000000000 0.000000000000 5000.000000000000 -3307.643800000000 -5953.102050000000 0.000000000000 0.000000000000 -13009.665000000001 -3307.643800000000 37592.652300000002 3910.963870000000 -15418.274400000000 13009.665000000001 0.000000000000 -5953.102050000000 3910.963870000000 42142.609400000001 9328.269530000000 3307.643800000000 5953.102050000000 0.000000000000 -15418.274400000000 9328.269530000000 9975.215819999999 34 45 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11928.147499999999 2164.406010000000 0.000000000000 5000.000000000000 0.000000000000 -11928.147499999999 0.000000000000 4955.815430000000 0.000000000000 0.000000000000 5000.000000000000 -2164.406010000000 -4955.815430000000 0.000000000000 0.000000000000 -11928.147499999999 -2164.406010000000 31084.404299999998 2181.965090000000 -11752.438500000000 11928.147499999999 0.000000000000 -4955.815430000000 2181.965090000000 34774.261700000003 5902.645020000000 2164.406010000000 4955.815430000000 0.000000000000 -11752.438500000000 5902.645020000000 7005.381840000000 34 52 55 4735.000000000000 0.000000000000 0.000000000000 0.000000000000 9726.809569999999 -494.331970000000 0.000000000000 4735.000000000000 0.000000000000 -9726.809569999999 0.000000000000 66.183082600000 0.000000000000 0.000000000000 4735.000000000000 494.331970000000 -66.183082600000 0.000000000000 0.000000000000 -9726.809569999999 494.331970000000 20582.435500000000 185.815933000000 225.542587000000 9726.809569999999 0.000000000000 -66.183082600000 185.815933000000 21336.455099999999 -1049.257570000000 -494.331970000000 66.183082600000 0.000000000000 225.542587000000 -1049.257570000000 1486.911500000000 35 36 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13995.832000000000 820.904663000000 0.000000000000 5000.000000000000 0.000000000000 -13995.832000000000 0.000000000000 5389.855960000000 0.000000000000 0.000000000000 5000.000000000000 -820.904663000000 -5389.855960000000 0.000000000000 0.000000000000 -13995.832000000000 -820.904663000000 41467.515599999999 1228.122800000000 -15622.926799999999 13995.832000000000 0.000000000000 -5389.855960000000 1228.122800000000 46821.109400000001 3117.850340000000 820.904663000000 5389.855960000000 0.000000000000 -15622.926799999999 3117.850340000000 7007.009280000000 35 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12679.196300000000 -327.740295000000 0.000000000000 5000.000000000000 0.000000000000 -12679.196300000000 0.000000000000 3719.492680000000 0.000000000000 0.000000000000 5000.000000000000 327.740295000000 -3719.492680000000 0.000000000000 0.000000000000 -12679.196300000000 327.740295000000 33138.726600000002 -234.852432000000 -9429.385740000000 12679.196300000000 0.000000000000 -3719.492680000000 -234.852432000000 36322.664100000002 -542.641052000000 -327.740295000000 3719.492680000000 0.000000000000 -9429.385740000000 -542.641052000000 3439.399660000000 35 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14406.825199999999 1230.014280000000 0.000000000000 5000.000000000000 0.000000000000 -14406.825199999999 0.000000000000 3899.085940000000 0.000000000000 0.000000000000 5000.000000000000 -1230.014280000000 -3899.085940000000 0.000000000000 0.000000000000 -14406.825199999999 -1230.014280000000 43817.144500000002 855.097656000000 -11094.872100000001 14406.825199999999 0.000000000000 -3899.085940000000 855.097656000000 46133.019500000002 4337.289550000000 1230.014280000000 3899.085940000000 0.000000000000 -11094.872100000001 4337.289550000000 4319.943850000000 35 45 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13175.059600000001 404.651581000000 0.000000000000 5000.000000000000 0.000000000000 -13175.059600000001 0.000000000000 2464.535640000000 0.000000000000 0.000000000000 5000.000000000000 -404.651581000000 -2464.535640000000 0.000000000000 0.000000000000 -13175.059600000001 -404.651581000000 37185.972699999998 44.779403700000 -6184.146000000000 13175.059600000001 0.000000000000 -2464.535640000000 44.779403700000 38279.117200000001 2025.357670000000 404.651581000000 2464.535640000000 0.000000000000 -6184.146000000000 2025.357670000000 2670.509280000000 35 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12376.275400000000 -58.922111500000 0.000000000000 5000.000000000000 0.000000000000 -12376.275400000000 0.000000000000 1023.001040000000 0.000000000000 0.000000000000 5000.000000000000 58.922111500000 -1023.001040000000 0.000000000000 0.000000000000 -12376.275400000000 58.922111500000 33595.855499999998 -258.130310000000 -2047.405880000000 12376.275400000000 0.000000000000 -1023.001040000000 -258.130310000000 33938.652300000002 1014.481140000000 -58.922111500000 1023.001040000000 0.000000000000 -2047.405880000000 1014.481140000000 1861.452270000000 35 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10967.427700000000 -1087.744630000000 0.000000000000 5000.000000000000 0.000000000000 -10967.427700000000 0.000000000000 699.336792000000 0.000000000000 0.000000000000 5000.000000000000 1087.744630000000 -699.336792000000 0.000000000000 0.000000000000 -10967.427700000000 1087.744630000000 25858.252000000000 -284.269043000000 -1055.885010000000 10967.427700000000 0.000000000000 -699.336792000000 -284.269043000000 26496.222699999998 -1909.679810000000 -1087.744630000000 699.336792000000 0.000000000000 -1055.885010000000 -1909.679810000000 1466.605830000000 36 37 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11886.271500000001 536.628174000000 0.000000000000 5000.000000000000 0.000000000000 -11886.271500000001 0.000000000000 4616.623050000000 0.000000000000 0.000000000000 5000.000000000000 -536.628174000000 -4616.623050000000 0.000000000000 0.000000000000 -11886.271500000001 -536.628174000000 30174.537100000001 759.957275000000 -10954.262699999999 11886.271500000001 0.000000000000 -4616.623050000000 759.957275000000 34192.652300000002 1665.067380000000 536.628174000000 4616.623050000000 0.000000000000 -10954.262699999999 1665.067380000000 5535.600590000000 36 43 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11608.089800000000 -715.632202000000 0.000000000000 5000.000000000000 0.000000000000 -11608.089800000000 0.000000000000 169.938400000000 0.000000000000 0.000000000000 5000.000000000000 715.632202000000 -169.938400000000 0.000000000000 0.000000000000 -11608.089800000000 715.632202000000 29454.875000000000 216.014969000000 -921.121826000000 11608.089800000000 0.000000000000 -169.938400000000 216.014969000000 31601.935500000000 -1638.412840000000 -715.632202000000 169.938400000000 0.000000000000 -921.121826000000 -1638.412840000000 3362.946530000000 36 44 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11716.697300000000 146.237839000000 0.000000000000 5000.000000000000 0.000000000000 -11716.697300000000 0.000000000000 -72.008659400000 0.000000000000 0.000000000000 5000.000000000000 -146.237839000000 72.008659400000 0.000000000000 0.000000000000 -11716.697300000000 -146.237839000000 29506.765599999999 269.718872000000 51.557174700000 11716.697300000000 0.000000000000 72.008659400000 269.718872000000 31607.906299999999 508.690979000000 146.237839000000 -72.008659400000 0.000000000000 51.557174700000 508.690979000000 3254.821530000000 36 45 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10747.603499999999 204.114319000000 0.000000000000 5000.000000000000 0.000000000000 -10747.603499999999 0.000000000000 -2046.712770000000 0.000000000000 0.000000000000 5000.000000000000 -204.114319000000 2046.712770000000 0.000000000000 0.000000000000 -10747.603499999999 -204.114319000000 25548.539100000002 -112.524940000000 4609.012210000000 10747.603499999999 0.000000000000 2046.712770000000 -112.524940000000 27228.513700000000 1146.343630000000 204.114319000000 -2046.712770000000 0.000000000000 4609.012210000000 1146.343630000000 3219.273930000000 37 42 55 3800.000000000000 0.000000000000 0.000000000000 0.000000000000 7162.895020000000 -565.176147000000 0.000000000000 3800.000000000000 0.000000000000 -7162.895020000000 0.000000000000 -737.273132000000 0.000000000000 0.000000000000 3800.000000000000 565.176147000000 737.273132000000 0.000000000000 0.000000000000 -7162.895020000000 565.176147000000 14020.544900000001 -9.459702490000 1445.103520000000 7162.895020000000 0.000000000000 737.273132000000 -9.459702490000 14618.227500000001 -999.811279000000 -565.176147000000 -737.273132000000 0.000000000000 1445.103520000000 -999.811279000000 855.148010000000 37 43 55 2964.000000000000 0.000000000000 0.000000000000 0.000000000000 4732.689940000000 -176.424606000000 0.000000000000 2964.000000000000 0.000000000000 -4732.689940000000 0.000000000000 -1441.481080000000 0.000000000000 0.000000000000 2964.000000000000 176.424606000000 1441.481080000000 0.000000000000 0.000000000000 -4732.689940000000 176.424606000000 7865.754390000000 19.188480400000 2400.741700000000 4732.689940000000 0.000000000000 1441.481080000000 19.188480400000 8740.302729999999 -282.933441000000 -176.424606000000 -1441.481080000000 0.000000000000 2400.741700000000 -282.933441000000 1115.698850000000 37 44 55 1581.000000000000 0.000000000000 0.000000000000 0.000000000000 2562.728030000000 -65.422142000000 0.000000000000 1581.000000000000 0.000000000000 -2562.728030000000 0.000000000000 -823.977295000000 0.000000000000 0.000000000000 1581.000000000000 65.422142000000 823.977295000000 0.000000000000 0.000000000000 -2562.728030000000 65.422142000000 4313.902830000000 -3.680376050000 1372.645390000000 2562.728030000000 0.000000000000 823.977295000000 -3.680376050000 4790.166990000000 -104.856651000000 -65.422142000000 -823.977295000000 0.000000000000 1372.645390000000 -104.856651000000 598.954956000000 38 42 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7475.833500000000 -1725.779660000000 0.000000000000 5000.000000000000 0.000000000000 -7475.833500000000 0.000000000000 -2295.508790000000 0.000000000000 0.000000000000 5000.000000000000 1725.779660000000 2295.508790000000 0.000000000000 0.000000000000 -7475.833500000000 1725.779660000000 12546.098599999999 679.806152000000 3703.754880000000 7475.833500000000 0.000000000000 2295.508790000000 679.806152000000 13422.915999999999 -2588.891110000000 -1725.779660000000 -2295.508790000000 0.000000000000 3703.754880000000 -2588.891110000000 2223.012940000000 39 44 55 1936.000000000000 0.000000000000 0.000000000000 0.000000000000 2740.261720000000 -100.081795000000 0.000000000000 1936.000000000000 0.000000000000 -2740.261720000000 0.000000000000 -1068.437010000000 0.000000000000 0.000000000000 1936.000000000000 100.081795000000 1068.437010000000 0.000000000000 0.000000000000 -2740.261720000000 100.081795000000 4149.963380000000 15.170601800000 1524.559450000000 2740.261720000000 0.000000000000 1068.437010000000 15.170601800000 4663.646480000000 -146.762756000000 -100.081795000000 -1068.437010000000 0.000000000000 1524.559450000000 -146.762756000000 748.104736000000 40 43 55 4170.000000000000 0.000000000000 0.000000000000 0.000000000000 6482.285160000000 350.787781000000 0.000000000000 4170.000000000000 0.000000000000 -6482.285160000000 0.000000000000 -2743.587890000000 0.000000000000 0.000000000000 4170.000000000000 -350.787781000000 2743.587890000000 0.000000000000 0.000000000000 -6482.285160000000 -350.787781000000 10955.579100000001 -367.985626000000 4345.405270000000 6482.285160000000 0.000000000000 2743.587890000000 -367.985626000000 12549.104499999999 748.724487000000 350.787781000000 -2743.587890000000 0.000000000000 4345.405270000000 748.724487000000 2254.299070000000 40 44 55 2667.000000000000 0.000000000000 0.000000000000 0.000000000000 4382.168460000000 689.090454000000 0.000000000000 2667.000000000000 0.000000000000 -4382.168460000000 0.000000000000 -2052.195800000000 0.000000000000 0.000000000000 2667.000000000000 -689.090454000000 2052.195800000000 0.000000000000 0.000000000000 -4382.168460000000 -689.090454000000 7782.113770000000 -573.905640000000 3387.629150000000 4382.168460000000 0.000000000000 2052.195800000000 -573.905640000000 9104.569340000000 1203.446170000000 689.090454000000 -2052.195800000000 0.000000000000 3387.629150000000 1203.446170000000 1920.273680000000 41 44 55 4400.000000000000 0.000000000000 0.000000000000 0.000000000000 6978.193850000000 931.983948000000 0.000000000000 4400.000000000000 0.000000000000 -6978.193850000000 0.000000000000 -3208.271970000000 0.000000000000 0.000000000000 4400.000000000000 -931.983948000000 3208.271970000000 0.000000000000 0.000000000000 -6978.193850000000 -931.983948000000 12042.126000000000 -695.991943000000 5042.328610000000 6978.193850000000 0.000000000000 3208.271970000000 -695.991943000000 13997.371100000000 1762.006470000000 931.983948000000 -3208.271970000000 0.000000000000 5042.328610000000 1762.006470000000 2940.538570000000 42 45 55 3179.000000000000 0.000000000000 0.000000000000 0.000000000000 6305.895020000000 1317.298580000000 0.000000000000 3179.000000000000 0.000000000000 -6305.895020000000 0.000000000000 -2221.218510000000 0.000000000000 0.000000000000 3179.000000000000 -1317.298580000000 2221.218510000000 0.000000000000 0.000000000000 -6305.895020000000 -1317.298580000000 13877.048800000000 -995.547180000000 4739.992190000000 6305.895020000000 0.000000000000 2221.218510000000 -995.547180000000 15167.224600000000 2878.492190000000 1317.298580000000 -2221.218510000000 0.000000000000 4739.992190000000 2878.492190000000 2803.786380000000 42 54 55 2689.000000000000 0.000000000000 0.000000000000 0.000000000000 5511.684080000000 1449.086180000000 0.000000000000 2689.000000000000 0.000000000000 -5511.684080000000 0.000000000000 -2483.980960000000 0.000000000000 0.000000000000 2689.000000000000 -1449.086180000000 2483.980960000000 0.000000000000 0.000000000000 -5511.684080000000 -1449.086180000000 12560.139600000000 -1308.093870000000 5034.791020000000 5511.684080000000 0.000000000000 2483.980960000000 -1308.093870000000 13964.162100000000 3153.678710000000 1449.086180000000 -2483.980960000000 0.000000000000 5034.791020000000 3153.678710000000 3210.575200000000 43 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11467.353499999999 3555.518310000000 0.000000000000 5000.000000000000 0.000000000000 -11467.353499999999 0.000000000000 -4729.902830000000 0.000000000000 0.000000000000 5000.000000000000 -3555.518310000000 4729.902830000000 0.000000000000 0.000000000000 -11467.353499999999 -3555.518310000000 30006.029299999998 -3623.628170000000 11060.489299999999 11467.353499999999 0.000000000000 4729.902830000000 -3623.628170000000 31581.527300000002 8710.283200000000 3555.518310000000 -4729.902830000000 0.000000000000 11060.489299999999 8710.283200000000 8047.276860000000 43 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11721.031300000001 3843.507570000000 0.000000000000 5000.000000000000 0.000000000000 -11721.031300000001 0.000000000000 -5171.986330000000 0.000000000000 0.000000000000 5000.000000000000 -3843.507570000000 5171.986330000000 0.000000000000 0.000000000000 -11721.031300000001 -3843.507570000000 31516.843799999999 -4176.647460000000 12335.096700000000 11721.031300000001 0.000000000000 5171.986330000000 -4176.647460000000 33580.132799999999 9509.425780000000 3843.507570000000 -5171.986330000000 0.000000000000 12335.096700000000 9509.425780000000 9282.794920000000 44 46 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11704.612300000001 -852.057861000000 0.000000000000 5000.000000000000 0.000000000000 -11704.612300000001 0.000000000000 -5600.495120000000 0.000000000000 0.000000000000 5000.000000000000 852.057861000000 5600.495120000000 0.000000000000 0.000000000000 -11704.612300000001 852.057861000000 28329.041000000001 866.511841000000 13322.621100000000 11704.612300000001 0.000000000000 5600.495120000000 866.511841000000 34502.445299999999 -1659.600710000000 -852.057861000000 -5600.495120000000 0.000000000000 13322.621100000000 -1659.600710000000 6907.024900000000 44 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11805.845700000000 -871.595459000000 0.000000000000 5000.000000000000 0.000000000000 -11805.845700000000 0.000000000000 -5880.692380000000 0.000000000000 0.000000000000 5000.000000000000 871.595459000000 5880.692380000000 0.000000000000 0.000000000000 -11805.845700000000 871.595459000000 28715.720700000002 964.755920000000 14049.849600000000 11805.845700000000 0.000000000000 5880.692380000000 964.755920000000 35472.621099999997 -1760.131350000000 -871.595459000000 -5880.692380000000 0.000000000000 14049.849600000000 -1760.131350000000 7459.935060000000 45 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11611.928700000000 -1016.667110000000 0.000000000000 5000.000000000000 0.000000000000 -11611.928700000000 0.000000000000 -5404.565920000000 0.000000000000 0.000000000000 5000.000000000000 1016.667110000000 5404.565920000000 0.000000000000 0.000000000000 -11611.928700000000 1016.667110000000 29075.310500000000 1056.071660000000 12754.208000000001 11611.928700000000 0.000000000000 5404.565920000000 1056.071660000000 34586.839800000002 -1665.429570000000 -1016.667110000000 -5404.565920000000 0.000000000000 12754.208000000001 -1665.429570000000 6825.383300000000 46 48 55 2084.000000000000 0.000000000000 0.000000000000 0.000000000000 6494.295410000000 -299.074646000000 0.000000000000 2084.000000000000 0.000000000000 -6494.295410000000 0.000000000000 -2762.674800000000 0.000000000000 0.000000000000 2084.000000000000 299.074646000000 2762.674800000000 0.000000000000 0.000000000000 -6494.295410000000 299.074646000000 21001.562500000000 321.931793000000 8643.921880000000 6494.295410000000 0.000000000000 2762.674800000000 321.931793000000 24241.611300000000 -851.509338000000 -299.074646000000 -2762.674800000000 0.000000000000 8643.921880000000 -851.509338000000 4156.653320000000 47 54 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11589.073200000001 -87.273002600000 0.000000000000 5000.000000000000 0.000000000000 -11589.073200000001 0.000000000000 2301.389890000000 0.000000000000 0.000000000000 5000.000000000000 87.273002600000 -2301.389890000000 0.000000000000 0.000000000000 -11589.073200000001 87.273002600000 29532.136699999999 293.586670000000 -5161.612300000000 11589.073200000001 0.000000000000 -2301.389890000000 293.586670000000 29655.964800000002 483.706848000000 -87.273002600000 2301.389890000000 0.000000000000 -5161.612300000000 483.706848000000 2720.944820000000 48 53 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13547.480500000000 866.403687000000 0.000000000000 5000.000000000000 0.000000000000 -13547.480500000000 0.000000000000 4847.918460000000 0.000000000000 0.000000000000 5000.000000000000 -866.403687000000 -4847.918460000000 0.000000000000 0.000000000000 -13547.480500000000 -866.403687000000 37974.386700000003 780.127808000000 -13100.344700000000 13547.480500000000 0.000000000000 -4847.918460000000 780.127808000000 41873.140599999999 2392.305660000000 866.403687000000 4847.918460000000 0.000000000000 -13100.344700000000 2392.305660000000 5904.937990000000 49 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13039.048800000000 -2809.705080000000 0.000000000000 5000.000000000000 0.000000000000 -13039.048800000000 0.000000000000 3243.279300000000 0.000000000000 0.000000000000 5000.000000000000 2809.705080000000 -3243.279300000000 0.000000000000 0.000000000000 -13039.048800000000 2809.705080000000 36568.476600000002 -1828.379270000000 -8363.600590000000 13039.048800000000 0.000000000000 -3243.279300000000 -1828.379270000000 37115.746099999997 -6981.372070000000 -2809.705080000000 3243.279300000000 0.000000000000 -8363.600590000000 -6981.372070000000 4676.507810000000 51 52 55 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13541.205099999999 -3653.645260000000 0.000000000000 5000.000000000000 0.000000000000 -13541.205099999999 0.000000000000 4791.219730000000 0.000000000000 0.000000000000 5000.000000000000 3653.645260000000 -4791.219730000000 0.000000000000 0.000000000000 -13541.205099999999 3653.645260000000 40727.902300000002 -3491.341310000000 -12822.854499999999 13541.205099999999 0.000000000000 -4791.219730000000 -3491.341310000000 42383.023399999998 -9385.450199999999 -3653.645260000000 4791.219730000000 0.000000000000 -12822.854499999999 -9385.450199999999 8319.645510000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-hotel_umd-maryland_hotel1/gt.info ================================================ 0 8 57 4010.000000000000 0.000000000000 0.000000000000 0.000000000000 8415.337890000001 240.678787000000 0.000000000000 4010.000000000000 0.000000000000 -8415.337890000001 0.000000000000 -3709.506100000000 0.000000000000 0.000000000000 4010.000000000000 -240.678787000000 3709.506100000000 0.000000000000 0.000000000000 -8415.337890000001 -240.678787000000 18928.718799999999 -297.971954000000 7994.689450000000 8415.337890000001 0.000000000000 3709.506100000000 -297.971954000000 21693.013700000000 776.400146000000 240.678787000000 -3709.506100000000 0.000000000000 7994.689450000000 776.400146000000 4495.236330000000 0 9 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10094.595700000000 -312.462006000000 0.000000000000 5000.000000000000 0.000000000000 -10094.595700000000 0.000000000000 -2676.681400000000 0.000000000000 0.000000000000 5000.000000000000 312.462006000000 2676.681400000000 0.000000000000 0.000000000000 -10094.595700000000 312.462006000000 21465.406299999999 -219.907043000000 5883.365230000000 10094.595700000000 0.000000000000 2676.681400000000 -219.907043000000 22987.636699999999 -270.299866000000 -312.462006000000 -2676.681400000000 0.000000000000 5883.365230000000 -270.299866000000 2661.900630000000 0 10 57 4475.000000000000 0.000000000000 0.000000000000 0.000000000000 8978.109380000000 65.924034100000 0.000000000000 4475.000000000000 0.000000000000 -8978.109380000000 0.000000000000 -1773.177250000000 0.000000000000 0.000000000000 4475.000000000000 -65.924034100000 1773.177250000000 0.000000000000 0.000000000000 -8978.109380000000 -65.924034100000 18714.083999999999 -520.903503000000 3933.399410000000 8978.109380000000 0.000000000000 1773.177250000000 -520.903503000000 20001.763700000000 333.710999000000 65.924034100000 -1773.177250000000 0.000000000000 3933.399410000000 333.710999000000 2297.596190000000 0 15 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10021.743200000001 -1334.694460000000 0.000000000000 5000.000000000000 0.000000000000 -10021.743200000001 0.000000000000 5334.877930000000 0.000000000000 0.000000000000 5000.000000000000 1334.694460000000 -5334.877930000000 0.000000000000 0.000000000000 -10021.743200000001 1334.694460000000 21490.998000000000 -1266.401860000000 -10697.492200000001 10021.743200000001 0.000000000000 -5334.877930000000 -1266.401860000000 26433.668000000001 -2829.689450000000 -1334.694460000000 5334.877930000000 0.000000000000 -10697.492200000001 -2829.689450000000 6757.629880000000 0 23 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8459.470700000000 -1431.032350000000 0.000000000000 5000.000000000000 0.000000000000 -8459.470700000000 0.000000000000 1194.984010000000 0.000000000000 0.000000000000 5000.000000000000 1431.032350000000 -1194.984010000000 0.000000000000 0.000000000000 -8459.470700000000 1431.032350000000 15572.274400000000 37.878376000000 -2393.856930000000 8459.470700000000 0.000000000000 -1194.984010000000 37.878376000000 16085.419900000001 -2062.965090000000 -1431.032350000000 1194.984010000000 0.000000000000 -2393.856930000000 -2062.965090000000 2118.461910000000 0 29 57 929.000000000000 0.000000000000 0.000000000000 0.000000000000 1787.944820000000 -1.508393530000 0.000000000000 929.000000000000 0.000000000000 -1787.944820000000 0.000000000000 -189.847549000000 0.000000000000 0.000000000000 929.000000000000 1.508393530000 189.847549000000 0.000000000000 0.000000000000 -1787.944820000000 1.508393530000 3470.027590000000 2.148357150000 364.205780000000 1787.944820000000 0.000000000000 189.847549000000 2.148357150000 3502.817870000000 -1.467463730000 -1.508393530000 -189.847549000000 0.000000000000 364.205780000000 -1.467463730000 85.526451100000 1 26 57 3305.000000000000 0.000000000000 0.000000000000 0.000000000000 6877.506350000000 1673.978520000000 0.000000000000 3305.000000000000 0.000000000000 -6877.506350000000 0.000000000000 -2041.789180000000 0.000000000000 0.000000000000 3305.000000000000 -1673.978520000000 2041.789180000000 0.000000000000 0.000000000000 -6877.506350000000 -1673.978520000000 15735.502899999999 -1162.422120000000 4216.082520000000 6877.506350000000 0.000000000000 2041.789180000000 -1162.422120000000 16057.548800000000 3670.673340000000 1673.978520000000 -2041.789180000000 0.000000000000 4216.082520000000 3670.673340000000 2695.104250000000 2 3 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9220.267580000000 -3901.999760000000 0.000000000000 5000.000000000000 0.000000000000 -9220.267580000000 0.000000000000 4202.797360000000 0.000000000000 0.000000000000 5000.000000000000 3901.999760000000 -4202.797360000000 0.000000000000 0.000000000000 -9220.267580000000 3901.999760000000 21790.043000000001 -2857.490970000000 -8042.705080000000 9220.267580000000 0.000000000000 -4202.797360000000 -2857.490970000000 21822.533200000002 -6961.194820000000 -3901.999760000000 4202.797360000000 0.000000000000 -8042.705080000000 -6961.194820000000 7967.936040000000 2 12 57 3748.000000000000 0.000000000000 0.000000000000 0.000000000000 6861.553710000000 -2830.602780000000 0.000000000000 3748.000000000000 0.000000000000 -6861.553710000000 0.000000000000 3952.407230000000 0.000000000000 0.000000000000 3748.000000000000 2830.602780000000 -3952.407230000000 0.000000000000 0.000000000000 -6861.553710000000 2830.602780000000 15801.308600000000 -2775.037600000000 -7381.901860000000 6861.553710000000 0.000000000000 -3952.407230000000 -2775.037600000000 17548.320299999999 -4933.870610000000 -2830.602780000000 3952.407230000000 0.000000000000 -7381.901860000000 -4933.870610000000 7236.898440000000 2 23 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11264.501000000000 -3675.958250000000 0.000000000000 5000.000000000000 0.000000000000 -11264.501000000000 0.000000000000 875.250244000000 0.000000000000 0.000000000000 5000.000000000000 3675.958250000000 -875.250244000000 0.000000000000 0.000000000000 -11264.501000000000 3675.958250000000 28912.685500000000 -565.160522000000 -1682.040040000000 11264.501000000000 0.000000000000 -875.250244000000 -565.160522000000 28082.943400000000 -8146.900880000000 -3675.958250000000 875.250244000000 0.000000000000 -1682.040040000000 -8146.900880000000 5257.475100000000 2 24 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11823.565399999999 -3456.672120000000 0.000000000000 5000.000000000000 0.000000000000 -11823.565399999999 0.000000000000 -5106.502440000000 0.000000000000 0.000000000000 5000.000000000000 3456.672120000000 5106.502440000000 0.000000000000 0.000000000000 -11823.565399999999 3456.672120000000 31282.099600000001 3386.538330000000 12175.957000000000 11823.565399999999 0.000000000000 5106.502440000000 3386.538330000000 33653.671900000001 -7896.699220000000 -3456.672120000000 -5106.502440000000 0.000000000000 12175.957000000000 -7896.699220000000 8349.742190000001 2 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10962.924800000001 -4424.645510000000 0.000000000000 5000.000000000000 0.000000000000 -10962.924800000001 0.000000000000 -4376.196290000000 0.000000000000 0.000000000000 5000.000000000000 4424.645510000000 4376.196290000000 0.000000000000 0.000000000000 -10962.924800000001 4424.645510000000 28903.966799999998 3757.101560000000 9940.848630000000 10962.924800000001 0.000000000000 4376.196290000000 3757.101560000000 28944.031299999999 -9440.078130000000 -4424.645510000000 -4376.196290000000 0.000000000000 9940.848630000000 -9440.078130000000 8223.732420000000 3 11 57 2103.000000000000 0.000000000000 0.000000000000 0.000000000000 3178.806400000000 179.852692000000 0.000000000000 2103.000000000000 0.000000000000 -3178.806400000000 0.000000000000 1140.768680000000 0.000000000000 0.000000000000 2103.000000000000 -179.852692000000 -1140.768680000000 0.000000000000 0.000000000000 -3178.806400000000 -179.852692000000 5418.574220000000 -111.541588000000 -1580.046260000000 3178.806400000000 0.000000000000 -1140.768680000000 -111.541588000000 5978.264650000000 493.238556000000 179.852692000000 1140.768680000000 0.000000000000 -1580.046260000000 493.238556000000 1182.905270000000 3 15 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11624.847700000000 769.156006000000 0.000000000000 5000.000000000000 0.000000000000 -11624.847700000000 0.000000000000 -4948.906250000000 0.000000000000 0.000000000000 5000.000000000000 -769.156006000000 4948.906250000000 0.000000000000 0.000000000000 -11624.847700000000 -769.156006000000 27905.162100000001 -741.605347000000 11529.586900000000 11624.847700000000 0.000000000000 4948.906250000000 -741.605347000000 32155.734400000001 1714.223020000000 769.156006000000 -4948.906250000000 0.000000000000 11529.586900000000 1714.223020000000 5721.581050000000 3 23 57 3146.000000000000 0.000000000000 0.000000000000 0.000000000000 7111.464360000000 1990.522830000000 0.000000000000 3146.000000000000 0.000000000000 -7111.464360000000 0.000000000000 -1857.571170000000 0.000000000000 0.000000000000 3146.000000000000 -1990.522830000000 1857.571170000000 0.000000000000 0.000000000000 -7111.464360000000 -1990.522830000000 17784.365200000000 -1171.311770000000 4242.478030000000 7111.464360000000 0.000000000000 1857.571170000000 -1171.311770000000 17610.798800000000 4628.987790000000 1990.522830000000 -1857.571170000000 0.000000000000 4242.478030000000 4628.987790000000 2901.946290000000 3 27 57 2351.000000000000 0.000000000000 0.000000000000 0.000000000000 4463.825680000000 -577.768005000000 0.000000000000 2351.000000000000 0.000000000000 -4463.825680000000 0.000000000000 357.272888000000 0.000000000000 0.000000000000 2351.000000000000 577.768005000000 -357.272888000000 0.000000000000 0.000000000000 -4463.825680000000 577.768005000000 9249.195309999999 -27.105691900000 -573.980957000000 4463.825680000000 0.000000000000 -357.272888000000 -27.105691900000 9393.210940000001 -988.123535000000 -577.768005000000 357.272888000000 0.000000000000 -573.980957000000 -988.123535000000 747.368103000000 3 28 57 2416.000000000000 0.000000000000 0.000000000000 0.000000000000 3882.295170000000 -323.659485000000 0.000000000000 2416.000000000000 0.000000000000 -3882.295170000000 0.000000000000 326.000275000000 0.000000000000 0.000000000000 2416.000000000000 323.659485000000 -326.000275000000 0.000000000000 0.000000000000 -3882.295170000000 323.659485000000 6884.560550000000 76.758903500000 -274.959015000000 3882.295170000000 0.000000000000 -326.000275000000 76.758903500000 7173.464840000000 -460.313721000000 -323.659485000000 326.000275000000 0.000000000000 -274.959015000000 -460.313721000000 1017.425350000000 4 11 57 3174.000000000000 0.000000000000 0.000000000000 0.000000000000 4981.021480000000 -3333.292970000000 0.000000000000 3174.000000000000 0.000000000000 -4981.021480000000 0.000000000000 663.648682000000 0.000000000000 0.000000000000 3174.000000000000 3333.292970000000 -663.648682000000 0.000000000000 0.000000000000 -4981.021480000000 3333.292970000000 12566.868200000001 -782.553894000000 -381.039398000000 4981.021480000000 0.000000000000 -663.648682000000 -782.553894000000 9573.705080000000 -4971.992680000000 -3333.292970000000 663.648682000000 0.000000000000 -381.039398000000 -4971.992680000000 4748.003910000000 4 12 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12230.690399999999 -4711.121580000000 0.000000000000 5000.000000000000 0.000000000000 -12230.690399999999 0.000000000000 -3285.724120000000 0.000000000000 0.000000000000 5000.000000000000 4711.121580000000 3285.724120000000 0.000000000000 0.000000000000 -12230.690399999999 4711.121580000000 35364.335899999998 2978.092040000000 8400.979490000000 12230.690399999999 0.000000000000 3285.724120000000 2978.092040000000 33801.312500000000 -11328.490200000000 -4711.121580000000 -3285.724120000000 0.000000000000 8400.979490000000 -11328.490200000000 8030.463380000000 4 16 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11588.697300000000 -4938.432620000000 0.000000000000 5000.000000000000 0.000000000000 -11588.697300000000 0.000000000000 -3854.332760000000 0.000000000000 0.000000000000 5000.000000000000 4938.432620000000 3854.332760000000 0.000000000000 0.000000000000 -11588.697300000000 4938.432620000000 32788.304700000001 3709.085450000000 9419.119140000001 11588.697300000000 0.000000000000 3854.332760000000 3709.085450000000 31179.423800000000 -11241.763700000000 -4938.432620000000 -3854.332760000000 0.000000000000 9419.119140000001 -11241.763700000000 8859.261720000000 4 28 57 4637.000000000000 0.000000000000 0.000000000000 0.000000000000 9347.703130000000 -2315.205810000000 0.000000000000 4637.000000000000 0.000000000000 -9347.703130000000 0.000000000000 206.248505000000 0.000000000000 0.000000000000 4637.000000000000 2315.205810000000 -206.248505000000 0.000000000000 0.000000000000 -9347.703130000000 2315.205810000000 23459.705099999999 -235.022736000000 157.285278000000 9347.703130000000 0.000000000000 -206.248505000000 -235.022736000000 21213.648399999998 -3290.858400000000 -2315.205810000000 206.248505000000 0.000000000000 157.285278000000 -3290.858400000000 3905.087890000000 5 7 57 2268.000000000000 0.000000000000 0.000000000000 0.000000000000 3843.085690000000 -1189.395140000000 0.000000000000 2268.000000000000 0.000000000000 -3843.085690000000 0.000000000000 2656.347900000000 0.000000000000 0.000000000000 2268.000000000000 1189.395140000000 -2656.347900000000 0.000000000000 0.000000000000 -3843.085690000000 1189.395140000000 7231.787110000000 -1362.441650000000 -4521.556640000000 3843.085690000000 0.000000000000 -2656.347900000000 -1362.441650000000 9805.818359999999 -1971.577390000000 -1189.395140000000 2656.347900000000 0.000000000000 -4521.556640000000 -1971.577390000000 3887.470210000000 5 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8873.246090000001 -2156.121830000000 0.000000000000 5000.000000000000 0.000000000000 -8873.246090000001 0.000000000000 834.260498000000 0.000000000000 0.000000000000 5000.000000000000 2156.121830000000 -834.260498000000 0.000000000000 0.000000000000 -8873.246090000001 2156.121830000000 17229.748000000000 -338.231140000000 -1474.181640000000 8873.246090000001 0.000000000000 -834.260498000000 -338.231140000000 16908.953099999999 -3868.106930000000 -2156.121830000000 834.260498000000 0.000000000000 -1474.181640000000 -3868.106930000000 2461.924560000000 5 33 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11038.297900000000 -710.100098000000 0.000000000000 5000.000000000000 0.000000000000 -11038.297900000000 0.000000000000 5222.439450000000 0.000000000000 0.000000000000 5000.000000000000 710.100098000000 -5222.439450000000 0.000000000000 0.000000000000 -11038.297900000000 710.100098000000 25160.527300000002 -574.237610000000 -11626.830099999999 11038.297900000000 0.000000000000 -5222.439450000000 -574.237610000000 30426.581999999999 -1388.037720000000 -710.100098000000 5222.439450000000 0.000000000000 -11626.830099999999 -1388.037720000000 6352.572270000000 5 34 57 3745.000000000000 0.000000000000 0.000000000000 0.000000000000 7572.045410000000 4757.966310000000 0.000000000000 3745.000000000000 0.000000000000 -7572.045410000000 0.000000000000 3437.210450000000 0.000000000000 0.000000000000 3745.000000000000 -4757.966310000000 -3437.210450000000 0.000000000000 0.000000000000 -7572.045410000000 -4757.966310000000 21471.158200000002 4410.159670000000 -7014.849610000000 7572.045410000000 0.000000000000 -3437.210450000000 4410.159670000000 18808.546900000001 9586.077149999999 4757.966310000000 3437.210450000000 0.000000000000 -7014.849610000000 9586.077149999999 9576.259770000001 5 35 57 3372.000000000000 0.000000000000 0.000000000000 0.000000000000 8209.856449999999 455.959442000000 0.000000000000 3372.000000000000 0.000000000000 -8209.856449999999 0.000000000000 3954.537350000000 0.000000000000 0.000000000000 3372.000000000000 -455.959442000000 -3954.537350000000 0.000000000000 0.000000000000 -8209.856449999999 -455.959442000000 20430.947300000000 618.277222000000 -9644.909180000001 8209.856449999999 0.000000000000 -3954.537350000000 618.277222000000 24939.203099999999 1051.303220000000 455.959442000000 3954.537350000000 0.000000000000 -9644.909180000001 1051.303220000000 5182.854490000000 6 7 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8894.197270000001 -5642.321780000000 0.000000000000 5000.000000000000 0.000000000000 -8894.197270000001 0.000000000000 5207.251460000000 0.000000000000 0.000000000000 5000.000000000000 5642.321780000000 -5207.251460000000 0.000000000000 0.000000000000 -8894.197270000001 5642.321780000000 23809.386699999999 -5782.745610000000 -9563.771479999999 8894.197270000001 0.000000000000 -5207.251460000000 -5782.745610000000 22946.900399999999 -10566.744100000000 -5642.321780000000 5207.251460000000 0.000000000000 -9563.771479999999 -10566.744100000000 12751.703100000001 6 19 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13923.229499999999 -2155.405520000000 0.000000000000 5000.000000000000 0.000000000000 -13923.229499999999 0.000000000000 5169.693850000000 0.000000000000 0.000000000000 5000.000000000000 2155.405520000000 -5169.693850000000 0.000000000000 0.000000000000 -13923.229499999999 2155.405520000000 43041.851600000002 -2421.427730000000 -14509.208000000001 13923.229499999999 0.000000000000 -5169.693850000000 -2421.427730000000 45576.921900000001 -5639.613280000000 -2155.405520000000 5169.693850000000 0.000000000000 -14509.208000000001 -5639.613280000000 8514.502930000001 6 22 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12531.703100000001 -5006.560060000000 0.000000000000 5000.000000000000 0.000000000000 -12531.703100000001 0.000000000000 -300.933685000000 0.000000000000 0.000000000000 5000.000000000000 5006.560060000000 300.933685000000 0.000000000000 0.000000000000 -12531.703100000001 5006.560060000000 37764.171900000001 -88.494590800000 784.159973000000 12531.703100000001 0.000000000000 300.933685000000 -88.494590800000 32624.839800000002 -12335.671899999999 -5006.560060000000 -300.933685000000 0.000000000000 784.159973000000 -12335.671899999999 6553.026860000000 6 33 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12339.726600000000 -5670.183110000000 0.000000000000 5000.000000000000 0.000000000000 -12339.726600000000 0.000000000000 627.752502000000 0.000000000000 0.000000000000 5000.000000000000 5670.183110000000 -627.752502000000 0.000000000000 0.000000000000 -12339.726600000000 5670.183110000000 38298.746099999997 -1173.985960000000 -1393.682370000000 12339.726600000000 0.000000000000 -627.752502000000 -1173.985960000000 31671.392599999999 -13586.510700000001 -5670.183110000000 627.752502000000 0.000000000000 -1393.682370000000 -13586.510700000001 7946.339360000000 6 34 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13378.711900000000 477.381470000000 0.000000000000 5000.000000000000 0.000000000000 -13378.711900000000 0.000000000000 -1420.746830000000 0.000000000000 0.000000000000 5000.000000000000 -477.381470000000 1420.746830000000 0.000000000000 0.000000000000 -13378.711900000000 -477.381470000000 36859.437500000000 -217.067657000000 3502.382810000000 13378.711900000000 0.000000000000 1420.746830000000 -217.067657000000 37069.273399999998 1171.966920000000 477.381470000000 -1420.746830000000 0.000000000000 3502.382810000000 1171.966920000000 1831.749150000000 6 35 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13662.686500000000 -5424.251950000000 0.000000000000 5000.000000000000 0.000000000000 -13662.686500000000 0.000000000000 1415.287110000000 0.000000000000 0.000000000000 5000.000000000000 5424.251950000000 -1415.287110000000 0.000000000000 0.000000000000 -13662.686500000000 5424.251950000000 44142.406300000002 -2004.773800000000 -4449.565920000000 13662.686500000000 0.000000000000 -1415.287110000000 -2004.773800000000 39949.531300000002 -14857.796899999999 -5424.251950000000 1415.287110000000 0.000000000000 -4449.565920000000 -14857.796899999999 8740.896479999999 6 36 57 3959.000000000000 0.000000000000 0.000000000000 0.000000000000 11364.344700000000 -3675.235350000000 0.000000000000 3959.000000000000 0.000000000000 -11364.344700000000 0.000000000000 5025.304200000000 0.000000000000 0.000000000000 3959.000000000000 3675.235350000000 -5025.304200000000 0.000000000000 0.000000000000 -11364.344700000000 3675.235350000000 37451.886700000003 -4812.097660000000 -14385.165999999999 11364.344700000000 0.000000000000 -5025.304200000000 -4812.097660000000 39671.855499999998 -10092.739299999999 -3675.235350000000 5025.304200000000 0.000000000000 -14385.165999999999 -10092.739299999999 10785.748000000000 6 37 57 3969.000000000000 0.000000000000 0.000000000000 0.000000000000 12492.530300000000 -1623.333130000000 0.000000000000 3969.000000000000 0.000000000000 -12492.530300000000 0.000000000000 4899.324220000000 0.000000000000 0.000000000000 3969.000000000000 1623.333130000000 -4899.324220000000 0.000000000000 0.000000000000 -12492.530300000000 1623.333130000000 41123.417999999998 -2170.481450000000 -15522.011699999999 12492.530300000000 0.000000000000 -4899.324220000000 -2170.481450000000 45754.359400000001 -4985.241210000000 -1623.333130000000 4899.324220000000 0.000000000000 -15522.011699999999 -4985.241210000000 7809.239750000000 7 8 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9604.137699999999 2044.053590000000 0.000000000000 5000.000000000000 0.000000000000 -9604.137699999999 0.000000000000 4261.475100000000 0.000000000000 0.000000000000 5000.000000000000 -2044.053590000000 -4261.475100000000 0.000000000000 0.000000000000 -9604.137699999999 -2044.053590000000 21063.720700000002 1666.502320000000 -8186.498540000000 9604.137699999999 0.000000000000 -4261.475100000000 1666.502320000000 23568.775399999999 4733.536620000000 2044.053590000000 4261.475100000000 0.000000000000 -8186.498540000000 4733.536620000000 6055.250490000000 7 9 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8452.626950000000 1231.416630000000 0.000000000000 5000.000000000000 0.000000000000 -8452.626950000000 0.000000000000 5422.532710000000 0.000000000000 0.000000000000 5000.000000000000 -1231.416630000000 -5422.532710000000 0.000000000000 0.000000000000 -8452.626950000000 -1231.416630000000 15441.478499999999 1479.012940000000 -9251.082030000000 8452.626950000000 0.000000000000 -5422.532710000000 1479.012940000000 20787.650399999999 2370.177980000000 1231.416630000000 5422.532710000000 0.000000000000 -9251.082030000000 2370.177980000000 7100.021970000000 7 10 57 4181.000000000000 0.000000000000 0.000000000000 0.000000000000 6604.296880000000 -77.999015800000 0.000000000000 4181.000000000000 0.000000000000 -6604.296880000000 0.000000000000 4292.935550000000 0.000000000000 0.000000000000 4181.000000000000 77.999015800000 -4292.935550000000 0.000000000000 0.000000000000 -6604.296880000000 77.999015800000 11200.868200000001 175.680710000000 -6953.929690000000 6604.296880000000 0.000000000000 -4292.935550000000 175.680710000000 15576.461900000000 130.987823000000 -77.999015800000 4292.935550000000 0.000000000000 -6953.929690000000 130.987823000000 5463.768070000000 7 11 57 3576.000000000000 0.000000000000 0.000000000000 0.000000000000 5854.053220000000 -1368.227780000000 0.000000000000 3576.000000000000 0.000000000000 -5854.053220000000 0.000000000000 117.921036000000 0.000000000000 0.000000000000 3576.000000000000 1368.227780000000 -117.921036000000 0.000000000000 0.000000000000 -5854.053220000000 1368.227780000000 10633.766600000001 0.869988084000 14.245040900000 5854.053220000000 0.000000000000 -117.921036000000 0.869988084000 10107.317400000000 -2232.291750000000 -1368.227780000000 117.921036000000 0.000000000000 14.245040900000 -2232.291750000000 1032.402590000000 7 13 57 2441.000000000000 0.000000000000 0.000000000000 0.000000000000 3600.948490000000 -680.193604000000 0.000000000000 2441.000000000000 0.000000000000 -3600.948490000000 0.000000000000 976.539673000000 0.000000000000 0.000000000000 2441.000000000000 680.193604000000 -976.539673000000 0.000000000000 0.000000000000 -3600.948490000000 680.193604000000 5741.896000000000 -322.660980000000 -1370.106450000000 3600.948490000000 0.000000000000 -976.539673000000 -322.660980000000 6101.355960000000 -959.497375000000 -680.193604000000 976.539673000000 0.000000000000 -1370.106450000000 -959.497375000000 1022.560240000000 7 18 57 3037.000000000000 0.000000000000 0.000000000000 0.000000000000 8155.215330000000 616.997742000000 0.000000000000 3037.000000000000 0.000000000000 -8155.215330000000 0.000000000000 -2186.799320000000 0.000000000000 0.000000000000 3037.000000000000 -616.997742000000 2186.799320000000 0.000000000000 0.000000000000 -8155.215330000000 -616.997742000000 23240.533200000002 -480.364014000000 6606.735350000000 8155.215330000000 0.000000000000 2186.799320000000 -480.364014000000 25230.773399999998 1909.614750000000 616.997742000000 -2186.799320000000 0.000000000000 6606.735350000000 1909.614750000000 2733.960690000000 7 20 57 4839.000000000000 0.000000000000 0.000000000000 0.000000000000 9719.409180000001 2958.159180000000 0.000000000000 4839.000000000000 0.000000000000 -9719.409180000001 0.000000000000 5688.622070000000 0.000000000000 0.000000000000 4839.000000000000 -2958.159180000000 -5688.622070000000 0.000000000000 0.000000000000 -9719.409180000001 -2958.159180000000 21929.308600000000 3448.976560000000 -11354.692400000000 9719.409180000001 0.000000000000 -5688.622070000000 3448.976560000000 26774.691400000000 6218.808110000000 2958.159180000000 5688.622070000000 0.000000000000 -11354.692400000000 6218.808110000000 8861.174800000001 7 21 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11126.445299999999 3651.812500000000 0.000000000000 5000.000000000000 0.000000000000 -11126.445299999999 0.000000000000 3700.291500000000 0.000000000000 0.000000000000 5000.000000000000 -3651.812500000000 -3700.291500000000 0.000000000000 0.000000000000 -11126.445299999999 -3651.812500000000 28135.871100000000 2753.540530000000 -8194.459960000000 11126.445299999999 0.000000000000 -3700.291500000000 2753.540530000000 29004.550800000001 8446.452149999999 3651.812500000000 3700.291500000000 0.000000000000 -8194.459960000000 8446.452149999999 6796.375000000000 7 22 57 2523.000000000000 0.000000000000 0.000000000000 0.000000000000 6425.763670000000 -7.914357660000 0.000000000000 2523.000000000000 0.000000000000 -6425.763670000000 0.000000000000 -2905.163090000000 0.000000000000 0.000000000000 2523.000000000000 7.914357660000 2905.163090000000 0.000000000000 0.000000000000 -6425.763670000000 7.914357660000 16747.636699999999 -107.266098000000 7590.812500000000 6425.763670000000 0.000000000000 2905.163090000000 -107.266098000000 20227.873000000000 121.952492000000 -7.914357660000 -2905.163090000000 0.000000000000 7590.812500000000 121.952492000000 3743.569820000000 7 29 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8219.069340000000 704.940613000000 0.000000000000 5000.000000000000 0.000000000000 -8219.069340000000 0.000000000000 3107.176030000000 0.000000000000 0.000000000000 5000.000000000000 -704.940613000000 -3107.176030000000 0.000000000000 0.000000000000 -8219.069340000000 -704.940613000000 14627.156300000001 550.850098000000 -4995.398440000000 8219.069340000000 0.000000000000 -3107.176030000000 550.850098000000 16261.962900000000 1511.198610000000 704.940613000000 3107.176030000000 0.000000000000 -4995.398440000000 1511.198610000000 3184.895260000000 7 30 57 4588.000000000000 0.000000000000 0.000000000000 0.000000000000 11322.488300000001 2633.968750000000 0.000000000000 4588.000000000000 0.000000000000 -11322.488300000001 0.000000000000 86.658065800000 0.000000000000 0.000000000000 4588.000000000000 -2633.968750000000 -86.658065800000 0.000000000000 0.000000000000 -11322.488300000001 -2633.968750000000 30470.099600000001 185.503632000000 55.830841100000 11322.488300000001 0.000000000000 -86.658065800000 185.503632000000 29473.642599999999 6707.820800000000 2633.968750000000 86.658065800000 0.000000000000 55.830841100000 6707.820800000000 3290.260740000000 7 31 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10634.877000000000 2712.510250000000 0.000000000000 5000.000000000000 0.000000000000 -10634.877000000000 0.000000000000 3920.678710000000 0.000000000000 0.000000000000 5000.000000000000 -2712.510250000000 -3920.678710000000 0.000000000000 0.000000000000 -10634.877000000000 -2712.510250000000 25296.439500000000 2688.332030000000 -8279.276370000000 10634.877000000000 0.000000000000 -3920.678710000000 2688.332030000000 27557.293000000001 6153.183590000000 2712.510250000000 3920.678710000000 0.000000000000 -8279.276370000000 6153.183590000000 6522.948240000000 7 32 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8461.454100000001 -2478.816160000000 0.000000000000 5000.000000000000 0.000000000000 -8461.454100000001 0.000000000000 -516.364441000000 0.000000000000 0.000000000000 5000.000000000000 2478.816160000000 516.364441000000 0.000000000000 0.000000000000 -8461.454100000001 2478.816160000000 16302.334999999999 327.057587000000 1405.246950000000 8461.454100000001 0.000000000000 516.364441000000 327.057587000000 15770.156300000001 -4154.109380000000 -2478.816160000000 -516.364441000000 0.000000000000 1405.246950000000 -4154.109380000000 2416.800780000000 7 36 57 4171.000000000000 0.000000000000 0.000000000000 0.000000000000 13067.842800000000 1458.196780000000 0.000000000000 4171.000000000000 0.000000000000 -13067.842800000000 0.000000000000 -4391.514650000000 0.000000000000 0.000000000000 4171.000000000000 -1458.196780000000 4391.514650000000 0.000000000000 0.000000000000 -13067.842800000000 -1458.196780000000 41713.886700000003 -1589.345830000000 13878.428700000000 13067.842800000000 0.000000000000 4391.514650000000 -1589.345830000000 45962.777300000002 4681.645510000000 1458.196780000000 -4391.514650000000 0.000000000000 13878.428700000000 4681.645510000000 5450.857420000000 7 37 57 3313.000000000000 0.000000000000 0.000000000000 0.000000000000 10760.967800000000 1425.131230000000 0.000000000000 3313.000000000000 0.000000000000 -10760.967800000000 0.000000000000 -3592.737060000000 0.000000000000 0.000000000000 3313.000000000000 -1425.131230000000 3592.737060000000 0.000000000000 0.000000000000 -10760.967800000000 -1425.131230000000 35679.296900000001 -1549.981450000000 11709.440399999999 10760.967800000000 0.000000000000 3592.737060000000 -1549.981450000000 39095.117200000001 4674.207030000000 1425.131230000000 -3592.737060000000 0.000000000000 11709.440399999999 4674.207030000000 4725.952640000000 8 10 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13643.317400000000 -750.701233000000 0.000000000000 5000.000000000000 0.000000000000 -13643.317400000000 0.000000000000 2081.319340000000 0.000000000000 0.000000000000 5000.000000000000 750.701233000000 -2081.319340000000 0.000000000000 0.000000000000 -13643.317400000000 750.701233000000 38982.246099999997 217.391281000000 -5472.139650000000 13643.317400000000 0.000000000000 -2081.319340000000 217.391281000000 39822.421900000001 -1828.122560000000 -750.701233000000 2081.319340000000 0.000000000000 -5472.139650000000 -1828.122560000000 3499.118900000000 8 19 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13712.491200000000 -2510.676760000000 0.000000000000 5000.000000000000 0.000000000000 -13712.491200000000 0.000000000000 -4015.264650000000 0.000000000000 0.000000000000 5000.000000000000 2510.676760000000 4015.264650000000 0.000000000000 0.000000000000 -13712.491200000000 2510.676760000000 40257.238299999997 1601.470460000000 11161.262699999999 13712.491200000000 0.000000000000 4015.264650000000 1601.470460000000 42496.871099999997 -6642.426760000000 -2510.676760000000 -4015.264650000000 0.000000000000 11161.262699999999 -6642.426760000000 6037.776370000000 8 20 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15030.283200000000 -2133.614750000000 0.000000000000 5000.000000000000 0.000000000000 -15030.283200000000 0.000000000000 -124.244270000000 0.000000000000 0.000000000000 5000.000000000000 2133.614750000000 124.244270000000 0.000000000000 0.000000000000 -15030.283200000000 2133.614750000000 46682.878900000003 265.817444000000 523.854980000000 15030.283200000000 0.000000000000 124.244270000000 265.817444000000 46758.332000000002 -6315.477540000000 -2133.614750000000 -124.244270000000 0.000000000000 523.854980000000 -6315.477540000000 2441.420900000000 8 21 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14287.293000000000 -2094.071530000000 0.000000000000 5000.000000000000 0.000000000000 -14287.293000000000 0.000000000000 -4006.544920000000 0.000000000000 0.000000000000 5000.000000000000 2094.071530000000 4006.544920000000 0.000000000000 0.000000000000 -14287.293000000000 2094.071530000000 43306.628900000003 1514.276490000000 11415.533200000000 14287.293000000000 0.000000000000 4006.544920000000 1514.276490000000 45984.972699999998 -5643.951660000000 -2094.071530000000 -4006.544920000000 0.000000000000 11415.533200000000 -5643.951660000000 5838.313480000000 8 26 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12243.336900000000 -2937.866460000000 0.000000000000 5000.000000000000 0.000000000000 -12243.336900000000 0.000000000000 3442.402830000000 0.000000000000 0.000000000000 5000.000000000000 2937.866460000000 -3442.402830000000 0.000000000000 0.000000000000 -12243.336900000000 2937.866460000000 33095.781300000002 -1694.433350000000 -8703.738280000000 12243.336900000000 0.000000000000 -3442.402830000000 -1694.433350000000 33373.039100000002 -6897.985350000000 -2937.866460000000 3442.402830000000 0.000000000000 -8703.738280000000 -6897.985350000000 5509.408200000000 8 31 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15452.536099999999 160.589035000000 0.000000000000 5000.000000000000 0.000000000000 -15452.536099999999 0.000000000000 -3324.191650000000 0.000000000000 0.000000000000 5000.000000000000 -160.589035000000 3324.191650000000 0.000000000000 0.000000000000 -15452.536099999999 -160.589035000000 50777.289100000002 611.602356000000 9835.954100000001 15452.536099999999 0.000000000000 3324.191650000000 611.602356000000 51956.207000000002 989.812134000000 160.589035000000 -3324.191650000000 0.000000000000 9835.954100000001 989.812134000000 6018.089360000000 9 14 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9538.843750000000 525.842590000000 0.000000000000 5000.000000000000 0.000000000000 -9538.843750000000 0.000000000000 1885.933230000000 0.000000000000 0.000000000000 5000.000000000000 -525.842590000000 -1885.933230000000 0.000000000000 0.000000000000 -9538.843750000000 -525.842590000000 19818.888700000000 -88.169921900000 -3103.811040000000 9538.843750000000 0.000000000000 -1885.933230000000 -88.169921900000 20269.144499999999 1590.886230000000 525.842590000000 1885.933230000000 0.000000000000 -3103.811040000000 1590.886230000000 1880.059200000000 9 19 57 4908.000000000000 0.000000000000 0.000000000000 0.000000000000 12023.604499999999 210.576965000000 0.000000000000 4908.000000000000 0.000000000000 -12023.604499999999 0.000000000000 -6182.821290000000 0.000000000000 0.000000000000 4908.000000000000 -210.576965000000 6182.821290000000 0.000000000000 0.000000000000 -12023.604499999999 -210.576965000000 30202.195299999999 -285.823730000000 15174.940399999999 12023.604499999999 0.000000000000 6182.821290000000 -285.823730000000 37859.527300000002 837.762024000000 210.576965000000 -6182.821290000000 0.000000000000 15174.940399999999 837.762024000000 8145.994630000000 9 20 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13136.445299999999 1693.826660000000 0.000000000000 5000.000000000000 0.000000000000 -13136.445299999999 0.000000000000 -5338.064450000000 0.000000000000 0.000000000000 5000.000000000000 -1693.826660000000 5338.064450000000 0.000000000000 0.000000000000 -13136.445299999999 -1693.826660000000 35757.445299999999 -1636.473140000000 14070.717800000000 13136.445299999999 0.000000000000 5338.064450000000 -1636.473140000000 40842.605499999998 4618.143550000000 1693.826660000000 -5338.064450000000 0.000000000000 14070.717800000000 4618.143550000000 7161.477540000000 9 21 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13128.017599999999 2068.039790000000 0.000000000000 5000.000000000000 0.000000000000 -13128.017599999999 0.000000000000 -6045.282230000000 0.000000000000 0.000000000000 5000.000000000000 -2068.039790000000 6045.282230000000 0.000000000000 0.000000000000 -13128.017599999999 -2068.039790000000 36434.992200000001 -2335.716550000000 15839.647499999999 13128.017599999999 0.000000000000 6045.282230000000 -2335.716550000000 42268.527300000002 5710.838870000000 2068.039790000000 -6045.282230000000 0.000000000000 15839.647499999999 5710.838870000000 9151.206050000001 9 24 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9211.366210000000 1304.038450000000 0.000000000000 5000.000000000000 0.000000000000 -9211.366210000000 0.000000000000 2936.809330000000 0.000000000000 0.000000000000 5000.000000000000 -1304.038450000000 -2936.809330000000 0.000000000000 0.000000000000 -9211.366210000000 -1304.038450000000 18632.300800000001 887.676270000000 -5355.909180000000 9211.366210000000 0.000000000000 -2936.809330000000 887.676270000000 19290.453099999999 2822.404300000000 1304.038450000000 2936.809330000000 0.000000000000 -5355.909180000000 2822.404300000000 3172.848140000000 9 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9182.493160000000 309.682678000000 0.000000000000 5000.000000000000 0.000000000000 -9182.493160000000 0.000000000000 1949.244510000000 0.000000000000 0.000000000000 5000.000000000000 -309.682678000000 -1949.244510000000 0.000000000000 0.000000000000 -9182.493160000000 -309.682678000000 18330.441400000000 268.806885000000 -3477.439450000000 9182.493160000000 0.000000000000 -1949.244510000000 268.806885000000 18671.505900000000 1032.994380000000 309.682678000000 1949.244510000000 0.000000000000 -3477.439450000000 1032.994380000000 1811.003050000000 9 29 57 4057.000000000000 0.000000000000 0.000000000000 0.000000000000 7503.343260000000 -937.228210000000 0.000000000000 4057.000000000000 0.000000000000 -7503.343260000000 0.000000000000 -3203.262450000000 0.000000000000 0.000000000000 4057.000000000000 937.228210000000 3203.262450000000 0.000000000000 0.000000000000 -7503.343260000000 937.228210000000 14409.806600000000 910.605652000000 6141.116210000000 7503.343260000000 0.000000000000 3203.262450000000 910.605652000000 18264.777300000002 -1688.865110000000 -937.228210000000 -3203.262450000000 0.000000000000 6141.116210000000 -1688.865110000000 4491.694340000000 9 31 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13499.015600000001 2451.145260000000 0.000000000000 5000.000000000000 0.000000000000 -13499.015600000001 0.000000000000 -6399.766110000000 0.000000000000 0.000000000000 5000.000000000000 -2451.145260000000 6399.766110000000 0.000000000000 0.000000000000 -13499.015600000001 -2451.145260000000 38739.515599999999 -3203.811520000000 17321.316400000000 13499.015600000001 0.000000000000 6399.766110000000 -3203.811520000000 45016.515599999999 6818.483890000000 2451.145260000000 -6399.766110000000 0.000000000000 17321.316400000000 6818.483890000000 10280.819299999999 10 13 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10884.502899999999 -2108.181400000000 0.000000000000 5000.000000000000 0.000000000000 -10884.502899999999 0.000000000000 -4529.849120000000 0.000000000000 0.000000000000 5000.000000000000 2108.181400000000 4529.849120000000 0.000000000000 0.000000000000 -10884.502899999999 2108.181400000000 26178.044900000001 1670.490720000000 11037.012699999999 10884.502899999999 0.000000000000 4529.849120000000 1670.490720000000 30670.939500000000 -4311.968260000000 -2108.181400000000 -4529.849120000000 0.000000000000 11037.012699999999 -4311.968260000000 6613.040530000000 10 14 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10508.636699999999 -355.602386000000 0.000000000000 5000.000000000000 0.000000000000 -10508.636699999999 0.000000000000 1968.204710000000 0.000000000000 0.000000000000 5000.000000000000 355.602386000000 -1968.204710000000 0.000000000000 0.000000000000 -10508.636699999999 355.602386000000 24093.673800000000 -190.897003000000 -3811.829100000000 10508.636699999999 0.000000000000 -1968.204710000000 -190.897003000000 24562.429700000001 -176.311768000000 -355.602386000000 1968.204710000000 0.000000000000 -3811.829100000000 -176.311768000000 1464.362790000000 10 19 57 2736.000000000000 0.000000000000 0.000000000000 0.000000000000 8859.233399999999 72.396446200000 0.000000000000 2736.000000000000 0.000000000000 -8859.233399999999 0.000000000000 -2589.908690000000 0.000000000000 0.000000000000 2736.000000000000 -72.396446200000 2589.908690000000 0.000000000000 0.000000000000 -8859.233399999999 -72.396446200000 28810.810500000000 -35.547351800000 8313.665040000000 8859.233399999999 0.000000000000 2589.908690000000 -35.547351800000 31489.789100000002 272.524200000000 72.396446200000 -2589.908690000000 0.000000000000 8313.665040000000 272.524200000000 2711.443360000000 10 20 57 4850.000000000000 0.000000000000 0.000000000000 0.000000000000 15757.893599999999 542.258423000000 0.000000000000 4850.000000000000 0.000000000000 -15757.893599999999 0.000000000000 -1617.632570000000 0.000000000000 0.000000000000 4850.000000000000 -542.258423000000 1617.632570000000 0.000000000000 0.000000000000 -15757.893599999999 -542.258423000000 51446.703099999999 -102.287254000000 5279.146480000000 15757.893599999999 0.000000000000 1617.632570000000 -102.287254000000 52198.070299999999 1778.541260000000 542.258423000000 -1617.632570000000 0.000000000000 5279.146480000000 1778.541260000000 1108.580200000000 10 21 57 1828.000000000000 0.000000000000 0.000000000000 0.000000000000 6120.310550000000 265.450836000000 0.000000000000 1828.000000000000 0.000000000000 -6120.310550000000 0.000000000000 -1540.860840000000 0.000000000000 0.000000000000 1828.000000000000 -265.450836000000 1540.860840000000 0.000000000000 0.000000000000 -6120.310550000000 -265.450836000000 20636.152300000002 -126.043915000000 5127.756350000000 6120.310550000000 0.000000000000 1540.860840000000 -126.043915000000 22025.363300000001 907.779846000000 265.450836000000 -1540.860840000000 0.000000000000 5127.756350000000 907.779846000000 1629.951660000000 10 23 57 1233.000000000000 0.000000000000 0.000000000000 0.000000000000 1916.846800000000 -328.390503000000 0.000000000000 1233.000000000000 0.000000000000 -1916.846800000000 0.000000000000 671.528748000000 0.000000000000 0.000000000000 1233.000000000000 328.390503000000 -671.528748000000 0.000000000000 0.000000000000 -1916.846800000000 328.390503000000 3266.481200000000 -123.982040000000 -1087.261350000000 1916.846800000000 0.000000000000 -671.528748000000 -123.982040000000 3502.225590000000 -422.636627000000 -328.390503000000 671.528748000000 0.000000000000 -1087.261350000000 -422.636627000000 639.525024000000 10 24 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9101.290040000000 -493.030762000000 0.000000000000 5000.000000000000 0.000000000000 -9101.290040000000 0.000000000000 2602.625980000000 0.000000000000 0.000000000000 5000.000000000000 493.030762000000 -2602.625980000000 0.000000000000 0.000000000000 -9101.290040000000 493.030762000000 18150.595700000002 -68.437240600000 -4828.711910000000 9101.290040000000 0.000000000000 -2602.625980000000 -68.437240600000 18827.169900000001 -264.550018000000 -493.030762000000 2602.625980000000 0.000000000000 -4828.711910000000 -264.550018000000 2313.047850000000 10 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9138.062500000000 -1211.274290000000 0.000000000000 5000.000000000000 0.000000000000 -9138.062500000000 0.000000000000 2052.480960000000 0.000000000000 0.000000000000 5000.000000000000 1211.274290000000 -2052.480960000000 0.000000000000 0.000000000000 -9138.062500000000 1211.274290000000 18332.236300000000 -384.336212000000 -3667.854490000000 9138.062500000000 0.000000000000 -2052.480960000000 -384.336212000000 18739.994100000000 -1818.964360000000 -1211.274290000000 2052.480960000000 0.000000000000 -3667.854490000000 -1818.964360000000 1745.306640000000 10 29 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8124.679690000000 -2401.774900000000 0.000000000000 5000.000000000000 0.000000000000 -8124.679690000000 0.000000000000 -1387.244630000000 0.000000000000 0.000000000000 5000.000000000000 2401.774900000000 1387.244630000000 0.000000000000 0.000000000000 -8124.679690000000 2401.774900000000 14873.115200000000 731.781067000000 2259.786870000000 8124.679690000000 0.000000000000 1387.244630000000 731.781067000000 14846.215800000000 -3755.888430000000 -2401.774900000000 -1387.244630000000 0.000000000000 2259.786870000000 -3755.888430000000 2440.751710000000 11 17 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11252.724600000000 -3494.882080000000 0.000000000000 5000.000000000000 0.000000000000 -11252.724600000000 0.000000000000 -3549.947510000000 0.000000000000 0.000000000000 5000.000000000000 3494.882080000000 3549.947510000000 0.000000000000 0.000000000000 -11252.724600000000 3494.882080000000 29935.871100000000 2578.107910000000 6850.293460000000 11252.724600000000 0.000000000000 3549.947510000000 2578.107910000000 31198.953099999999 -7861.250490000000 -3494.882080000000 -3549.947510000000 0.000000000000 6850.293460000000 -7861.250490000000 6934.548830000000 11 18 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14699.586900000000 -2727.535640000000 0.000000000000 5000.000000000000 0.000000000000 -14699.586900000000 0.000000000000 774.385620000000 0.000000000000 0.000000000000 5000.000000000000 2727.535640000000 -774.385620000000 0.000000000000 0.000000000000 -14699.586900000000 2727.535640000000 45545.390599999999 -411.285370000000 -2456.482670000000 14699.586900000000 0.000000000000 -774.385620000000 -411.285370000000 44835.695299999999 -8061.810550000000 -2727.535640000000 774.385620000000 0.000000000000 -2456.482670000000 -8061.810550000000 3243.231200000000 11 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12911.229499999999 -2726.805910000000 0.000000000000 5000.000000000000 0.000000000000 -12911.229499999999 0.000000000000 -163.573959000000 0.000000000000 0.000000000000 5000.000000000000 2726.805910000000 163.573959000000 0.000000000000 0.000000000000 -12911.229499999999 2726.805910000000 36121.753900000003 -165.194595000000 -199.708237000000 12911.229499999999 0.000000000000 163.573959000000 -165.194595000000 35457.933599999997 -7004.229490000000 -2726.805910000000 -163.573959000000 0.000000000000 -199.708237000000 -7004.229490000000 3127.863040000000 11 28 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12936.740200000000 -2677.173830000000 0.000000000000 5000.000000000000 0.000000000000 -12936.740200000000 0.000000000000 -1306.478390000000 0.000000000000 0.000000000000 5000.000000000000 2677.173830000000 1306.478390000000 0.000000000000 0.000000000000 -12936.740200000000 2677.173830000000 36573.609400000001 144.373413000000 2765.151860000000 12936.740200000000 0.000000000000 1306.478390000000 144.373413000000 35507.429700000001 -7118.004880000000 -2677.173830000000 -1306.478390000000 0.000000000000 2765.151860000000 -7118.004880000000 3538.364750000000 11 32 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13947.623000000000 -3175.045170000000 0.000000000000 5000.000000000000 0.000000000000 -13947.623000000000 0.000000000000 878.863281000000 0.000000000000 0.000000000000 5000.000000000000 3175.045170000000 -878.863281000000 0.000000000000 0.000000000000 -13947.623000000000 3175.045170000000 41833.738299999997 -649.145203000000 -2971.066890000000 13947.623000000000 0.000000000000 -878.863281000000 -649.145203000000 40990.007799999999 -8775.249019999999 -3175.045170000000 878.863281000000 0.000000000000 -2971.066890000000 -8775.249019999999 3736.126710000000 12 15 57 3658.000000000000 0.000000000000 0.000000000000 0.000000000000 6070.445800000000 -1439.876950000000 0.000000000000 3658.000000000000 0.000000000000 -6070.445800000000 0.000000000000 -1867.173830000000 0.000000000000 0.000000000000 3658.000000000000 1439.876950000000 1867.173830000000 0.000000000000 0.000000000000 -6070.445800000000 1439.876950000000 11127.466800000000 692.838013000000 3079.870610000000 6070.445800000000 0.000000000000 1867.173830000000 692.838013000000 11175.182600000000 -2454.224610000000 -1439.876950000000 -1867.173830000000 0.000000000000 3079.870610000000 -2454.224610000000 1975.034670000000 12 23 57 3702.000000000000 0.000000000000 0.000000000000 0.000000000000 7337.296390000000 -874.864136000000 0.000000000000 3702.000000000000 0.000000000000 -7337.296390000000 0.000000000000 -143.201202000000 0.000000000000 0.000000000000 3702.000000000000 874.864136000000 143.201202000000 0.000000000000 0.000000000000 -7337.296390000000 874.864136000000 15515.707000000000 -123.305542000000 486.237488000000 7337.296390000000 0.000000000000 143.201202000000 -123.305542000000 15148.255900000000 -1630.488280000000 -874.864136000000 -143.201202000000 0.000000000000 486.237488000000 -1630.488280000000 1174.373900000000 12 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8520.516600000001 -4264.460450000000 0.000000000000 5000.000000000000 0.000000000000 -8520.516600000001 0.000000000000 5199.129880000000 0.000000000000 0.000000000000 5000.000000000000 4264.460450000000 -5199.129880000000 0.000000000000 0.000000000000 -8520.516600000001 4264.460450000000 18810.705099999999 -4430.419430000000 -8796.949220000000 8520.516600000001 0.000000000000 -5199.129880000000 -4430.419430000000 20936.296900000001 -7067.205570000000 -4264.460450000000 5199.129880000000 0.000000000000 -8796.949220000000 -7067.205570000000 9964.447270000001 12 28 57 3881.000000000000 0.000000000000 0.000000000000 0.000000000000 6760.444820000000 -2390.804930000000 0.000000000000 3881.000000000000 0.000000000000 -6760.444820000000 0.000000000000 3365.843020000000 0.000000000000 0.000000000000 3881.000000000000 2390.804930000000 -3365.843020000000 0.000000000000 0.000000000000 -6760.444820000000 2390.804930000000 14534.532200000000 -2048.467040000000 -5903.529300000000 6760.444820000000 0.000000000000 -3365.843020000000 -2048.467040000000 15556.162100000000 -3650.498290000000 -2390.804930000000 3365.843020000000 0.000000000000 -5903.529300000000 -3650.498290000000 5666.221680000000 12 29 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8078.384280000000 -4349.852050000000 0.000000000000 5000.000000000000 0.000000000000 -8078.384280000000 0.000000000000 4977.563960000000 0.000000000000 0.000000000000 5000.000000000000 4349.852050000000 -4977.563960000000 0.000000000000 0.000000000000 -8078.384280000000 4349.852050000000 17292.742200000001 -4546.878420000000 -7974.433590000000 8078.384280000000 0.000000000000 -4977.563960000000 -4546.878420000000 18710.206999999999 -6935.511720000000 -4349.852050000000 4977.563960000000 0.000000000000 -7974.433590000000 -6935.511720000000 9557.531250000000 13 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 4803.017090000000 -1907.399540000000 0.000000000000 5000.000000000000 0.000000000000 -4803.017090000000 0.000000000000 5077.312990000000 0.000000000000 0.000000000000 5000.000000000000 1907.399540000000 -5077.312990000000 0.000000000000 0.000000000000 -4803.017090000000 1907.399540000000 5751.303220000000 -1910.537350000000 -4846.271000000000 4803.017090000000 0.000000000000 -5077.312990000000 -1910.537350000000 10392.506799999999 -1669.259890000000 -1907.399540000000 5077.312990000000 0.000000000000 -4846.271000000000 -1669.259890000000 6274.561520000000 13 26 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6214.417480000000 -1943.598390000000 0.000000000000 5000.000000000000 0.000000000000 -6214.417480000000 0.000000000000 4008.136720000000 0.000000000000 0.000000000000 5000.000000000000 1943.598390000000 -4008.136720000000 0.000000000000 0.000000000000 -6214.417480000000 1943.598390000000 9368.890630000000 -1407.080080000000 -4641.628910000000 6214.417480000000 0.000000000000 -4008.136720000000 -1407.080080000000 12236.351600000000 -2493.578130000000 -1943.598390000000 4008.136720000000 0.000000000000 -4641.628910000000 -2493.578130000000 4642.282230000000 14 15 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7159.760250000000 -1169.238890000000 0.000000000000 5000.000000000000 0.000000000000 -7159.760250000000 0.000000000000 4736.006840000000 0.000000000000 0.000000000000 5000.000000000000 1169.238890000000 -4736.006840000000 0.000000000000 0.000000000000 -7159.760250000000 1169.238890000000 11607.986300000000 -794.152161000000 -6743.234860000000 7159.760250000000 0.000000000000 -4736.006840000000 -794.152161000000 15649.414100000000 -1681.242800000000 -1169.238890000000 4736.006840000000 0.000000000000 -6743.234860000000 -1681.242800000000 5780.104000000000 14 29 57 588.000000000000 0.000000000000 0.000000000000 0.000000000000 1168.130250000000 18.340507500000 0.000000000000 588.000000000000 0.000000000000 -1168.130250000000 0.000000000000 -211.854492000000 0.000000000000 0.000000000000 588.000000000000 -18.340507500000 211.854492000000 0.000000000000 0.000000000000 -1168.130250000000 -18.340507500000 2346.523930000000 0.245931655000 424.238647000000 1168.130250000000 0.000000000000 211.854492000000 0.245931655000 2422.098140000000 37.034126300000 18.340507500000 -211.854492000000 0.000000000000 424.238647000000 37.034126300000 118.624863000000 15 24 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9173.622069999999 1440.849370000000 0.000000000000 5000.000000000000 0.000000000000 -9173.622069999999 0.000000000000 -2236.759520000000 0.000000000000 0.000000000000 5000.000000000000 -1440.849370000000 2236.759520000000 0.000000000000 0.000000000000 -9173.622069999999 -1440.849370000000 18231.918000000001 -624.156982000000 4115.264160000000 9173.622069999999 0.000000000000 2236.759520000000 -624.156982000000 18255.697300000000 2807.363770000000 1440.849370000000 -2236.759520000000 0.000000000000 4115.264160000000 2807.363770000000 2204.975590000000 15 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8881.500000000000 937.406311000000 0.000000000000 5000.000000000000 0.000000000000 -8881.500000000000 0.000000000000 -1794.788210000000 0.000000000000 0.000000000000 5000.000000000000 -937.406311000000 1794.788210000000 0.000000000000 0.000000000000 -8881.500000000000 -937.406311000000 16998.580099999999 -345.894775000000 3297.446040000000 8881.500000000000 0.000000000000 1794.788210000000 -345.894775000000 17069.777300000002 2047.406740000000 937.406311000000 -1794.788210000000 0.000000000000 3297.446040000000 2047.406740000000 1589.564700000000 17 18 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6903.292970000000 -2282.962160000000 0.000000000000 5000.000000000000 0.000000000000 -6903.292970000000 0.000000000000 5240.090330000000 0.000000000000 0.000000000000 5000.000000000000 2282.962160000000 -5240.090330000000 0.000000000000 0.000000000000 -6903.292970000000 2282.962160000000 11530.400400000000 -2238.183110000000 -7099.109380000000 6903.292970000000 0.000000000000 -5240.090330000000 -2238.183110000000 15461.759800000000 -3252.493650000000 -2282.962160000000 5240.090330000000 0.000000000000 -7099.109380000000 -3252.493650000000 7404.730470000000 17 22 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7893.629880000000 -2537.991700000000 0.000000000000 5000.000000000000 0.000000000000 -7893.629880000000 0.000000000000 4270.890140000000 0.000000000000 0.000000000000 5000.000000000000 2537.991700000000 -4270.890140000000 0.000000000000 0.000000000000 -7893.629880000000 2537.991700000000 15034.261699999999 -1890.873050000000 -6146.880370000000 7893.629880000000 0.000000000000 -4270.890140000000 -1890.873050000000 17807.484400000001 -4056.458250000000 -2537.991700000000 4270.890140000000 0.000000000000 -6146.880370000000 -4056.458250000000 6510.712400000000 17 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8645.221680000001 -3174.980960000000 0.000000000000 5000.000000000000 0.000000000000 -8645.221680000001 0.000000000000 2862.857420000000 0.000000000000 0.000000000000 5000.000000000000 3174.980960000000 -2862.857420000000 0.000000000000 0.000000000000 -8645.221680000001 3174.980960000000 18969.636699999999 -2218.244870000000 -3813.423830000000 8645.221680000001 0.000000000000 -2862.857420000000 -2218.244870000000 19516.818400000000 -4921.033690000000 -3174.980960000000 2862.857420000000 0.000000000000 -3813.423830000000 -4921.033690000000 5711.576170000000 17 29 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10523.166999999999 -1982.213380000000 0.000000000000 5000.000000000000 0.000000000000 -10523.166999999999 0.000000000000 -1276.223390000000 0.000000000000 0.000000000000 5000.000000000000 1982.213380000000 1276.223390000000 0.000000000000 0.000000000000 -10523.166999999999 1982.213380000000 24213.877000000000 63.300281500000 2977.255860000000 10523.166999999999 0.000000000000 1276.223390000000 63.300281500000 23678.595700000002 -3845.815670000000 -1982.213380000000 -1276.223390000000 0.000000000000 2977.255860000000 -3845.815670000000 2417.923580000000 17 32 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7258.927730000000 -3904.538820000000 0.000000000000 5000.000000000000 0.000000000000 -7258.927730000000 0.000000000000 4495.691410000000 0.000000000000 0.000000000000 5000.000000000000 3904.538820000000 -4495.691410000000 0.000000000000 0.000000000000 -7258.927730000000 3904.538820000000 14327.861300000000 -3601.530760000000 -6198.552730000000 7258.927730000000 0.000000000000 -4495.691410000000 -3601.530760000000 15785.552700000000 -5468.194340000000 -3904.538820000000 4495.691410000000 0.000000000000 -6198.552730000000 -5468.194340000000 8104.014160000000 18 19 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12090.985400000000 2231.581050000000 0.000000000000 5000.000000000000 0.000000000000 -12090.985400000000 0.000000000000 5212.188480000000 0.000000000000 0.000000000000 5000.000000000000 -2231.581050000000 -5212.188480000000 0.000000000000 0.000000000000 -12090.985400000000 -2231.581050000000 34674.789100000002 2219.367430000000 -12333.910200000000 12090.985400000000 0.000000000000 -5212.188480000000 2219.367430000000 38037.031300000002 6463.087890000000 2231.581050000000 5212.188480000000 0.000000000000 -12333.910200000000 6463.087890000000 8024.571290000000 18 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9536.918949999999 -2402.166260000000 0.000000000000 5000.000000000000 0.000000000000 -9536.918949999999 0.000000000000 -2643.051510000000 0.000000000000 0.000000000000 5000.000000000000 2402.166260000000 2643.051510000000 0.000000000000 0.000000000000 -9536.918949999999 2402.166260000000 19893.687500000000 1190.331790000000 4963.056150000000 9536.918949999999 0.000000000000 2643.051510000000 1190.331790000000 20244.095700000002 -4533.087400000000 -2402.166260000000 -2643.051510000000 0.000000000000 4963.056150000000 -4533.087400000000 3392.333250000000 18 28 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9964.176760000000 -1180.009160000000 0.000000000000 5000.000000000000 0.000000000000 -9964.176760000000 0.000000000000 -3109.086910000000 0.000000000000 0.000000000000 5000.000000000000 1180.009160000000 3109.086910000000 0.000000000000 0.000000000000 -9964.176760000000 1180.009160000000 21318.560500000000 460.160339000000 6063.657710000000 9964.176760000000 0.000000000000 3109.086910000000 460.160339000000 22538.365200000000 -2352.008790000000 -1180.009160000000 -3109.086910000000 0.000000000000 6063.657710000000 -2352.008790000000 3464.571290000000 18 32 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9808.805660000000 -1933.475460000000 0.000000000000 5000.000000000000 0.000000000000 -9808.805660000000 0.000000000000 -3309.269780000000 0.000000000000 0.000000000000 5000.000000000000 1933.475460000000 3309.269780000000 0.000000000000 0.000000000000 -9808.805660000000 1933.475460000000 21023.488300000001 1403.395750000000 6267.423340000000 9808.805660000000 0.000000000000 3309.269780000000 1403.395750000000 22354.543000000001 -3492.816410000000 -1933.475460000000 -3309.269780000000 0.000000000000 6267.423340000000 -3492.816410000000 3968.109620000000 18 33 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13581.240200000000 323.227936000000 0.000000000000 5000.000000000000 0.000000000000 -13581.240200000000 0.000000000000 -895.037354000000 0.000000000000 0.000000000000 5000.000000000000 -323.227936000000 895.037354000000 0.000000000000 0.000000000000 -13581.240200000000 -323.227936000000 38211.410199999998 -59.777950300000 2243.474610000000 13581.240200000000 0.000000000000 895.037354000000 -59.777950300000 37935.531300000002 1125.109010000000 323.227936000000 -895.037354000000 0.000000000000 2243.474610000000 1125.109010000000 1552.190670000000 18 35 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14855.980500000000 1732.260500000000 0.000000000000 5000.000000000000 0.000000000000 -14855.980500000000 0.000000000000 378.220001000000 0.000000000000 0.000000000000 5000.000000000000 -1732.260500000000 -378.220001000000 0.000000000000 0.000000000000 -14855.980500000000 -1732.260500000000 45674.953099999999 196.718719000000 -1743.059570000000 14855.980500000000 0.000000000000 -378.220001000000 196.718719000000 46344.097699999998 5088.059080000000 1732.260500000000 378.220001000000 0.000000000000 -1743.059570000000 5088.059080000000 3028.895750000000 18 36 57 3529.000000000000 0.000000000000 0.000000000000 0.000000000000 11137.938500000000 1657.761720000000 0.000000000000 3529.000000000000 0.000000000000 -11137.938500000000 0.000000000000 4255.039060000000 0.000000000000 0.000000000000 3529.000000000000 -1657.761720000000 -4255.039060000000 0.000000000000 0.000000000000 -11137.938500000000 -1657.761720000000 36426.109400000001 1962.730710000000 -13471.985400000000 11137.938500000000 0.000000000000 -4255.039060000000 1962.730710000000 40543.847699999998 5276.291020000000 1657.761720000000 4255.039060000000 0.000000000000 -13471.985400000000 5276.291020000000 6378.164060000000 19 20 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7983.199220000000 -2717.379390000000 0.000000000000 5000.000000000000 0.000000000000 -7983.199220000000 0.000000000000 4614.012210000000 0.000000000000 0.000000000000 5000.000000000000 2717.379390000000 -4614.012210000000 0.000000000000 0.000000000000 -7983.199220000000 2717.379390000000 15336.040999999999 -2303.486080000000 -7590.023930000000 7983.199220000000 0.000000000000 -4614.012210000000 -2303.486080000000 18294.335899999998 -4035.937260000000 -2717.379390000000 4614.012210000000 0.000000000000 -7590.023930000000 -4035.937260000000 6365.947750000000 19 30 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9946.146479999999 -1315.684690000000 0.000000000000 5000.000000000000 0.000000000000 -9946.146479999999 0.000000000000 4388.979000000000 0.000000000000 0.000000000000 5000.000000000000 1315.684690000000 -4388.979000000000 0.000000000000 0.000000000000 -9946.146479999999 1315.684690000000 21357.074199999999 -1413.542480000000 -8283.500980000001 9946.146479999999 0.000000000000 -4388.979000000000 -1413.542480000000 25424.285199999998 -2326.951660000000 -1315.684690000000 4388.979000000000 0.000000000000 -8283.500980000001 -2326.951660000000 5910.346680000000 19 35 57 3128.000000000000 0.000000000000 0.000000000000 0.000000000000 10011.211900000000 -2958.046390000000 0.000000000000 3128.000000000000 0.000000000000 -10011.211900000000 0.000000000000 -4107.959470000000 0.000000000000 0.000000000000 3128.000000000000 2958.046390000000 4107.959470000000 0.000000000000 0.000000000000 -10011.211900000000 2958.046390000000 35354.695299999999 3789.856930000000 13119.982400000001 10011.211900000000 0.000000000000 4107.959470000000 3789.856930000000 37579.988299999997 -9501.007809999999 -2958.046390000000 -4107.959470000000 0.000000000000 13119.982400000001 -9501.007809999999 8659.131840000000 19 36 57 4651.000000000000 0.000000000000 0.000000000000 0.000000000000 15143.784200000000 -4027.036870000000 0.000000000000 4651.000000000000 0.000000000000 -15143.784200000000 0.000000000000 -5880.481930000000 0.000000000000 0.000000000000 4651.000000000000 4027.036870000000 5880.481930000000 0.000000000000 0.000000000000 -15143.784200000000 4027.036870000000 53765.921900000001 4837.304200000000 19130.429700000001 15143.784200000000 0.000000000000 5880.481930000000 4837.304200000000 56970.035199999998 -13166.685500000000 -4027.036870000000 -5880.481930000000 0.000000000000 19130.429700000001 -13166.685500000000 11915.431600000000 19 37 57 3594.000000000000 0.000000000000 0.000000000000 0.000000000000 11730.082000000000 -2266.086430000000 0.000000000000 3594.000000000000 0.000000000000 -11730.082000000000 0.000000000000 -4755.372070000000 0.000000000000 0.000000000000 3594.000000000000 2266.086430000000 4755.372070000000 0.000000000000 0.000000000000 -11730.082000000000 2266.086430000000 40611.269500000002 2791.916500000000 15473.376000000000 11730.082000000000 0.000000000000 4755.372070000000 2791.916500000000 44747.480499999998 -7568.066890000000 -2266.086430000000 -4755.372070000000 0.000000000000 15473.376000000000 -7568.066890000000 8612.768550000001 22 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10923.586900000000 -1194.961180000000 0.000000000000 5000.000000000000 0.000000000000 -10923.586900000000 0.000000000000 -3607.080320000000 0.000000000000 0.000000000000 5000.000000000000 1194.961180000000 3607.080320000000 0.000000000000 0.000000000000 -10923.586900000000 1194.961180000000 25462.916000000001 1188.121950000000 7638.770020000000 10923.586900000000 0.000000000000 3607.080320000000 1188.121950000000 27940.718799999999 -2307.337160000000 -1194.961180000000 -3607.080320000000 0.000000000000 7638.770020000000 -2307.337160000000 4585.030760000000 22 33 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15100.666999999999 2405.837160000000 0.000000000000 5000.000000000000 0.000000000000 -15100.666999999999 0.000000000000 1904.084960000000 0.000000000000 0.000000000000 5000.000000000000 -2405.837160000000 -1904.084960000000 0.000000000000 0.000000000000 -15100.666999999999 -2405.837160000000 48066.203099999999 1006.264470000000 -5886.324220000000 15100.666999999999 0.000000000000 -1904.084960000000 1006.264470000000 47320.683599999997 7477.516600000000 2405.837160000000 1904.084960000000 0.000000000000 -5886.324220000000 7477.516600000000 3727.985350000000 22 35 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15757.259800000000 3808.093020000000 0.000000000000 5000.000000000000 0.000000000000 -15757.259800000000 0.000000000000 2132.116700000000 0.000000000000 0.000000000000 5000.000000000000 -3808.093020000000 -2132.116700000000 0.000000000000 0.000000000000 -15757.259800000000 -3808.093020000000 53516.320299999999 1657.353760000000 -6812.677250000000 15757.259800000000 0.000000000000 -2132.116700000000 1657.353760000000 51503.265599999999 11909.139600000000 3808.093020000000 2132.116700000000 0.000000000000 -6812.677250000000 11909.139600000000 5458.690430000000 23 24 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8635.425780000000 1.248515730000 0.000000000000 5000.000000000000 0.000000000000 -8635.425780000000 0.000000000000 -2861.019780000000 0.000000000000 0.000000000000 5000.000000000000 -1.248515730000 2861.019780000000 0.000000000000 0.000000000000 -8635.425780000000 -1.248515730000 16523.138700000000 -553.764526000000 5502.056150000000 8635.425780000000 0.000000000000 2861.019780000000 -553.764526000000 18616.193400000000 461.522186000000 1.248515730000 -2861.019780000000 0.000000000000 5502.056150000000 461.522186000000 3056.424800000000 23 25 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9054.596680000001 -3.565820220000 0.000000000000 5000.000000000000 0.000000000000 -9054.596680000001 0.000000000000 -1642.968260000000 0.000000000000 0.000000000000 5000.000000000000 3.565820220000 1642.968260000000 0.000000000000 0.000000000000 -9054.596680000001 3.565820220000 17595.964800000002 -458.324799000000 3540.239010000000 9054.596680000001 0.000000000000 1642.968260000000 -458.324799000000 19476.458999999999 380.314667000000 -3.565820220000 -1642.968260000000 0.000000000000 3540.239010000000 380.314667000000 2489.851560000000 23 26 57 2340.000000000000 0.000000000000 0.000000000000 0.000000000000 3240.013180000000 -402.391724000000 0.000000000000 2340.000000000000 0.000000000000 -3240.013180000000 0.000000000000 -643.055542000000 0.000000000000 0.000000000000 2340.000000000000 402.391724000000 643.055542000000 0.000000000000 0.000000000000 -3240.013180000000 402.391724000000 5018.486820000000 -81.078804000000 1043.572630000000 3240.013180000000 0.000000000000 643.055542000000 -81.078804000000 6003.886230000000 -479.976807000000 -402.391724000000 -643.055542000000 0.000000000000 1043.572630000000 -479.976807000000 1261.826660000000 23 29 57 1302.000000000000 0.000000000000 0.000000000000 0.000000000000 2955.245120000000 380.170288000000 0.000000000000 1302.000000000000 0.000000000000 -2955.245120000000 0.000000000000 932.597168000000 0.000000000000 0.000000000000 1302.000000000000 -380.170288000000 -932.597168000000 0.000000000000 0.000000000000 -2955.245120000000 -380.170288000000 7448.023440000000 429.974121000000 -2644.894530000000 2955.245120000000 0.000000000000 -932.597168000000 429.974121000000 8484.891600000001 1010.810670000000 380.170288000000 932.597168000000 0.000000000000 -2644.894530000000 1010.810670000000 1492.216310000000 25 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8069.259770000000 -790.037170000000 0.000000000000 5000.000000000000 0.000000000000 -8069.259770000000 0.000000000000 1897.170290000000 0.000000000000 0.000000000000 5000.000000000000 790.037170000000 -1897.170290000000 0.000000000000 0.000000000000 -8069.259770000000 790.037170000000 14251.704100000001 -227.157089000000 -3175.942140000000 8069.259770000000 0.000000000000 -1897.170290000000 -227.157089000000 14751.803700000000 -823.176453000000 -790.037170000000 1897.170290000000 0.000000000000 -3175.942140000000 -823.176453000000 1228.397830000000 25 29 57 2685.000000000000 0.000000000000 0.000000000000 0.000000000000 4413.022950000000 -1121.656620000000 0.000000000000 2685.000000000000 0.000000000000 -4413.022950000000 0.000000000000 -1375.664430000000 0.000000000000 0.000000000000 2685.000000000000 1121.656620000000 1375.664430000000 0.000000000000 0.000000000000 -4413.022950000000 1121.656620000000 8550.714840000001 774.965942000000 2268.624270000000 4413.022950000000 0.000000000000 1375.664430000000 774.965942000000 8367.318359999999 -1658.380370000000 -1121.656620000000 -1375.664430000000 0.000000000000 2268.624270000000 -1658.380370000000 2160.055180000000 25 32 57 3492.000000000000 0.000000000000 0.000000000000 0.000000000000 4572.324220000000 -1266.693240000000 0.000000000000 3492.000000000000 0.000000000000 -4572.324220000000 0.000000000000 192.691620000000 0.000000000000 0.000000000000 3492.000000000000 1266.693240000000 -192.691620000000 0.000000000000 0.000000000000 -4572.324220000000 1266.693240000000 6599.790530000000 -54.557922400000 -193.909119000000 4572.324220000000 0.000000000000 -192.691620000000 -54.557922400000 6369.869140000000 -1611.925290000000 -1266.693240000000 192.691620000000 0.000000000000 -193.909119000000 -1611.925290000000 756.556091000000 26 27 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8462.949220000000 -1718.856570000000 0.000000000000 5000.000000000000 0.000000000000 -8462.949220000000 0.000000000000 5202.037110000000 0.000000000000 0.000000000000 5000.000000000000 1718.856570000000 -5202.037110000000 0.000000000000 0.000000000000 -8462.949220000000 1718.856570000000 16806.111300000000 -1527.309690000000 -8943.510740000000 8462.949220000000 0.000000000000 -5202.037110000000 -1527.309690000000 20867.494100000000 -2143.948490000000 -1718.856570000000 5202.037110000000 0.000000000000 -8943.510740000000 -2143.948490000000 7633.002440000000 26 32 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8401.920899999999 -1415.645020000000 0.000000000000 5000.000000000000 0.000000000000 -8401.920899999999 0.000000000000 4042.864260000000 0.000000000000 0.000000000000 5000.000000000000 1415.645020000000 -4042.864260000000 0.000000000000 0.000000000000 -8401.920899999999 1415.645020000000 15889.140600000001 -1434.598880000000 -6675.167970000000 8401.920899999999 0.000000000000 -4042.864260000000 -1434.598880000000 18976.429700000001 -1848.402470000000 -1415.645020000000 4042.864260000000 0.000000000000 -6675.167970000000 -1848.402470000000 5399.433110000000 28 33 57 3679.000000000000 0.000000000000 0.000000000000 0.000000000000 4812.230470000000 -4231.718260000000 0.000000000000 3679.000000000000 0.000000000000 -4812.230470000000 0.000000000000 1784.908080000000 0.000000000000 0.000000000000 3679.000000000000 4231.718260000000 -1784.908080000000 0.000000000000 0.000000000000 -4812.230470000000 4231.718260000000 11348.296899999999 -1968.911380000000 -2392.517580000000 4812.230470000000 0.000000000000 -1784.908080000000 -1968.911380000000 7401.939940000000 -5478.761720000000 -4231.718260000000 1784.908080000000 0.000000000000 -2392.517580000000 -5478.761720000000 6021.270020000000 32 33 57 3400.000000000000 0.000000000000 0.000000000000 0.000000000000 3807.599120000000 -826.396362000000 0.000000000000 3400.000000000000 0.000000000000 -3807.599120000000 0.000000000000 3398.773190000000 0.000000000000 0.000000000000 3400.000000000000 826.396362000000 -3398.773190000000 0.000000000000 0.000000000000 -3807.599120000000 826.396362000000 5300.666500000000 -663.189392000000 -3765.889650000000 3807.599120000000 0.000000000000 -3398.773190000000 -663.189392000000 8290.994140000001 -815.056702000000 -826.396362000000 3398.773190000000 0.000000000000 -3765.889650000000 -815.056702000000 4204.416020000000 35 36 57 3642.000000000000 0.000000000000 0.000000000000 0.000000000000 4141.398930000000 -1582.200070000000 0.000000000000 3642.000000000000 0.000000000000 -4141.398930000000 0.000000000000 2916.133540000000 0.000000000000 0.000000000000 3642.000000000000 1582.200070000000 -2916.133540000000 0.000000000000 0.000000000000 -4141.398930000000 1582.200070000000 5782.722170000000 -1366.664790000000 -3407.541750000000 4141.398930000000 0.000000000000 -2916.133540000000 -1366.664790000000 7352.881840000000 -1956.694950000000 -1582.200070000000 2916.133540000000 0.000000000000 -3407.541750000000 -1956.694950000000 3478.750490000000 35 37 57 1901.000000000000 0.000000000000 0.000000000000 0.000000000000 2031.063110000000 -627.485718000000 0.000000000000 1901.000000000000 0.000000000000 -2031.063110000000 0.000000000000 1576.596070000000 0.000000000000 0.000000000000 1901.000000000000 627.485718000000 -1576.596070000000 0.000000000000 0.000000000000 -2031.063110000000 627.485718000000 2586.473140000000 -607.933167000000 -1754.657230000000 2031.063110000000 0.000000000000 -1576.596070000000 -607.933167000000 3658.723390000000 -764.041016000000 -627.485718000000 1576.596070000000 0.000000000000 -1754.657230000000 -764.041016000000 1766.387330000000 36 38 57 4718.000000000000 0.000000000000 0.000000000000 0.000000000000 10754.592800000000 988.689209000000 0.000000000000 4718.000000000000 0.000000000000 -10754.592800000000 0.000000000000 1217.633180000000 0.000000000000 0.000000000000 4718.000000000000 -988.689209000000 -1217.633180000000 0.000000000000 0.000000000000 -10754.592800000000 -988.689209000000 25156.638700000000 228.860809000000 -2810.995850000000 10754.592800000000 0.000000000000 -1217.633180000000 228.860809000000 25359.367200000001 2322.328610000000 988.689209000000 1217.633180000000 0.000000000000 -2810.995850000000 2322.328610000000 1001.992980000000 36 39 57 2993.000000000000 0.000000000000 0.000000000000 0.000000000000 6223.530760000000 519.183167000000 0.000000000000 2993.000000000000 0.000000000000 -6223.530760000000 0.000000000000 17.493356700000 0.000000000000 0.000000000000 2993.000000000000 -519.183167000000 -17.493356700000 0.000000000000 0.000000000000 -6223.530760000000 -519.183167000000 13637.059600000001 18.012888000000 -163.077545000000 6223.530760000000 0.000000000000 -17.493356700000 18.012888000000 13448.894500000000 1112.297000000000 519.183167000000 17.493356700000 0.000000000000 -163.077545000000 1112.297000000000 302.046967000000 36 42 57 2358.000000000000 0.000000000000 0.000000000000 0.000000000000 4876.571290000000 516.410217000000 0.000000000000 2358.000000000000 0.000000000000 -4876.571290000000 0.000000000000 2699.323970000000 0.000000000000 0.000000000000 2358.000000000000 -516.410217000000 -2699.323970000000 0.000000000000 0.000000000000 -4876.571290000000 -516.410217000000 10461.263700000000 602.903748000000 -5591.134770000000 4876.571290000000 0.000000000000 -2699.323970000000 602.903748000000 13282.275400000000 1160.858760000000 516.410217000000 2699.323970000000 0.000000000000 -5591.134770000000 1160.858760000000 3421.778810000000 36 53 57 2744.000000000000 0.000000000000 0.000000000000 0.000000000000 6236.703130000000 803.763000000000 0.000000000000 2744.000000000000 0.000000000000 -6236.703130000000 0.000000000000 2881.421630000000 0.000000000000 0.000000000000 2744.000000000000 -803.763000000000 -2881.421630000000 0.000000000000 0.000000000000 -6236.703130000000 -803.763000000000 14589.756799999999 775.386292000000 -6432.062010000000 6236.703130000000 0.000000000000 -2881.421630000000 775.386292000000 17474.123000000000 1907.442020000000 803.763000000000 2881.421630000000 0.000000000000 -6432.062010000000 1907.442020000000 3466.928710000000 36 55 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11952.450199999999 1664.456910000000 0.000000000000 5000.000000000000 0.000000000000 -11952.450199999999 0.000000000000 3468.352050000000 0.000000000000 0.000000000000 5000.000000000000 -1664.456910000000 -3468.352050000000 0.000000000000 0.000000000000 -11952.450199999999 -1664.456910000000 29522.246100000000 1123.933590000000 -8149.458980000000 11952.450199999999 0.000000000000 -3468.352050000000 1123.933590000000 31773.896499999999 4149.715330000000 1664.456910000000 3468.352050000000 0.000000000000 -8149.458980000000 4149.715330000000 3708.051030000000 36 56 57 3436.000000000000 0.000000000000 0.000000000000 0.000000000000 6735.013180000000 222.455109000000 0.000000000000 3436.000000000000 0.000000000000 -6735.013180000000 0.000000000000 60.367656700000 0.000000000000 0.000000000000 3436.000000000000 -222.455109000000 -60.367656700000 0.000000000000 0.000000000000 -6735.013180000000 -222.455109000000 13582.290000000001 -16.433038700000 -193.761871000000 6735.013180000000 0.000000000000 -60.367656700000 -16.433038700000 13448.097700000000 438.936615000000 222.455109000000 60.367656700000 0.000000000000 -193.761871000000 438.936615000000 293.598419000000 37 38 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12480.932600000000 44.152027100000 0.000000000000 5000.000000000000 0.000000000000 -12480.932600000000 0.000000000000 -1787.257570000000 0.000000000000 0.000000000000 5000.000000000000 -44.152027100000 1787.257570000000 0.000000000000 0.000000000000 -12480.932600000000 -44.152027100000 31934.689500000000 -115.572144000000 4391.364260000000 12480.932600000000 0.000000000000 1787.257570000000 -115.572144000000 32592.611300000000 66.624900800000 44.152027100000 -1787.257570000000 0.000000000000 4391.364260000000 66.624900800000 1240.956180000000 37 39 57 4206.000000000000 0.000000000000 0.000000000000 0.000000000000 8796.404300000000 416.375031000000 0.000000000000 4206.000000000000 0.000000000000 -8796.404300000000 0.000000000000 -2147.405270000000 0.000000000000 0.000000000000 4206.000000000000 -416.375031000000 2147.405270000000 0.000000000000 0.000000000000 -8796.404300000000 -416.375031000000 19960.330099999999 -326.390747000000 4493.632320000000 8796.404300000000 0.000000000000 2147.405270000000 -326.390747000000 20414.722699999998 557.863403000000 416.375031000000 -2147.405270000000 0.000000000000 4493.632320000000 557.863403000000 1840.757200000000 37 41 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14061.852500000001 1135.929930000000 0.000000000000 5000.000000000000 0.000000000000 -14061.852500000001 0.000000000000 195.699249000000 0.000000000000 0.000000000000 5000.000000000000 -1135.929930000000 -195.699249000000 0.000000000000 0.000000000000 -14061.852500000001 -1135.929930000000 40288.039100000002 178.741486000000 -610.601074000000 14061.852500000001 0.000000000000 -195.699249000000 178.741486000000 40391.554700000001 3261.775880000000 1135.929930000000 195.699249000000 0.000000000000 -610.601074000000 3261.775880000000 1317.340580000000 37 42 57 3360.000000000000 0.000000000000 0.000000000000 0.000000000000 8626.033200000000 486.739624000000 0.000000000000 3360.000000000000 0.000000000000 -8626.033200000000 0.000000000000 1955.765500000000 0.000000000000 0.000000000000 3360.000000000000 -486.739624000000 -1955.765500000000 0.000000000000 0.000000000000 -8626.033200000000 -486.739624000000 22753.378900000000 241.268799000000 -4991.089360000000 8626.033200000000 0.000000000000 -1955.765500000000 241.268799000000 23529.958999999999 1359.734990000000 486.739624000000 1955.765500000000 0.000000000000 -4991.089360000000 1359.734990000000 1591.876220000000 37 55 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13510.430700000001 292.837311000000 0.000000000000 5000.000000000000 0.000000000000 -13510.430700000001 0.000000000000 448.190186000000 0.000000000000 0.000000000000 5000.000000000000 -292.837311000000 -448.190186000000 0.000000000000 0.000000000000 -13510.430700000001 -292.837311000000 37059.257799999999 -10.914595600000 -1059.014400000000 13510.430700000001 0.000000000000 -448.190186000000 -10.914595600000 37596.242200000001 1018.603700000000 292.837311000000 448.190186000000 0.000000000000 -1059.014400000000 1018.603700000000 984.586914000000 37 56 57 4413.000000000000 0.000000000000 0.000000000000 0.000000000000 9144.784180000001 93.734428400000 0.000000000000 4413.000000000000 0.000000000000 -9144.784180000001 0.000000000000 -2059.953860000000 0.000000000000 0.000000000000 4413.000000000000 -93.734428400000 2059.953860000000 0.000000000000 0.000000000000 -9144.784180000001 -93.734428400000 19933.101600000002 -250.348389000000 4201.038090000000 9144.784180000001 0.000000000000 2059.953860000000 -250.348389000000 20299.134800000000 20.285629300000 93.734428400000 -2059.953860000000 0.000000000000 4201.038090000000 20.285629300000 1776.929200000000 38 55 57 3427.000000000000 0.000000000000 0.000000000000 0.000000000000 6378.737300000000 -1276.703130000000 0.000000000000 3427.000000000000 0.000000000000 -6378.737300000000 0.000000000000 1243.568240000000 0.000000000000 0.000000000000 3427.000000000000 1276.703130000000 -1243.568240000000 0.000000000000 0.000000000000 -6378.737300000000 1276.703130000000 12572.472700000000 -498.355896000000 -2258.954100000000 6378.737300000000 0.000000000000 -1243.568240000000 -498.355896000000 12547.199199999999 -2275.768310000000 -1276.703130000000 1243.568240000000 0.000000000000 -2258.954100000000 -2275.768310000000 1121.769170000000 40 41 57 4518.000000000000 0.000000000000 0.000000000000 0.000000000000 6638.005370000000 -4391.726560000000 0.000000000000 4518.000000000000 0.000000000000 -6638.005370000000 0.000000000000 2577.088380000000 0.000000000000 0.000000000000 4518.000000000000 4391.726560000000 -2577.088380000000 0.000000000000 0.000000000000 -6638.005370000000 4391.726560000000 14468.803700000000 -2597.759520000000 -3770.614500000000 6638.005370000000 0.000000000000 -2577.088380000000 -2597.759520000000 11440.533200000000 -6510.899900000000 -4391.726560000000 2577.088380000000 0.000000000000 -3770.614500000000 -6510.899900000000 6159.944820000000 41 42 57 577.000000000000 0.000000000000 0.000000000000 0.000000000000 626.578247000000 -226.388840000000 0.000000000000 577.000000000000 0.000000000000 -626.578247000000 0.000000000000 510.630859000000 0.000000000000 0.000000000000 577.000000000000 226.388840000000 -510.630859000000 0.000000000000 0.000000000000 -626.578247000000 226.388840000000 808.512146000000 -198.977036000000 -556.281799000000 626.578247000000 0.000000000000 -510.630859000000 -198.977036000000 1145.302250000000 -243.100327000000 -226.388840000000 510.630859000000 0.000000000000 -556.281799000000 -243.100327000000 571.882141000000 41 53 57 1748.000000000000 0.000000000000 0.000000000000 0.000000000000 2210.161380000000 -740.627136000000 0.000000000000 1748.000000000000 0.000000000000 -2210.161380000000 0.000000000000 1239.610230000000 0.000000000000 0.000000000000 1748.000000000000 740.627136000000 -1239.610230000000 0.000000000000 0.000000000000 -2210.161380000000 740.627136000000 3153.598140000000 -536.252441000000 -1542.292600000000 2210.161380000000 0.000000000000 -1239.610230000000 -536.252441000000 3745.195560000000 -916.167480000000 -740.627136000000 1239.610230000000 0.000000000000 -1542.292600000000 -916.167480000000 1257.387700000000 41 55 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6854.814450000000 -2201.348390000000 0.000000000000 5000.000000000000 0.000000000000 -6854.814450000000 0.000000000000 1693.523560000000 0.000000000000 0.000000000000 5000.000000000000 2201.348390000000 -1693.523560000000 0.000000000000 0.000000000000 -6854.814450000000 2201.348390000000 10673.775400000000 -855.616272000000 -2092.885740000000 6854.814450000000 0.000000000000 -1693.523560000000 -855.616272000000 10609.403300000000 -2890.965090000000 -2201.348390000000 1693.523560000000 0.000000000000 -2092.885740000000 -2890.965090000000 2138.593020000000 42 53 57 2971.000000000000 0.000000000000 0.000000000000 0.000000000000 4810.235350000000 -238.938293000000 0.000000000000 2971.000000000000 0.000000000000 -4810.235350000000 0.000000000000 -140.960907000000 0.000000000000 0.000000000000 2971.000000000000 238.938293000000 140.960907000000 0.000000000000 0.000000000000 -4810.235350000000 238.938293000000 8551.588870000000 -4.410181520000 228.238831000000 4810.235350000000 0.000000000000 140.960907000000 -4.410181520000 8023.205080000000 -220.298065000000 -238.938293000000 -140.960907000000 0.000000000000 228.238831000000 -220.298065000000 625.002747000000 42 55 57 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7521.281740000000 -751.481384000000 0.000000000000 5000.000000000000 0.000000000000 -7521.281740000000 0.000000000000 1349.386600000000 0.000000000000 0.000000000000 5000.000000000000 751.481384000000 -1349.386600000000 0.000000000000 0.000000000000 -7521.281740000000 751.481384000000 12145.867200000001 -325.689240000000 -1922.605960000000 7521.281740000000 0.000000000000 -1349.386600000000 -325.689240000000 12496.657200000000 -1002.814210000000 -751.481384000000 1349.386600000000 0.000000000000 -1922.605960000000 -1002.814210000000 1334.135500000000 43 45 57 1167.000000000000 0.000000000000 0.000000000000 0.000000000000 1557.032230000000 681.097656000000 0.000000000000 1167.000000000000 0.000000000000 -1557.032230000000 0.000000000000 148.102600000000 0.000000000000 0.000000000000 1167.000000000000 -681.097656000000 -148.102600000000 0.000000000000 0.000000000000 -1557.032230000000 -681.097656000000 2730.110350000000 52.826973000000 -135.254745000000 1557.032230000000 0.000000000000 -148.102600000000 52.826973000000 2304.905270000000 978.157471000000 681.097656000000 148.102600000000 0.000000000000 -135.254745000000 978.157471000000 527.935852000000 43 48 57 2104.000000000000 0.000000000000 0.000000000000 0.000000000000 3369.459960000000 2206.573000000000 0.000000000000 2104.000000000000 0.000000000000 -3369.459960000000 0.000000000000 -1399.681640000000 0.000000000000 0.000000000000 2104.000000000000 -2206.573000000000 1399.681640000000 0.000000000000 0.000000000000 -3369.459960000000 -2206.573000000000 7922.990230000000 -1362.772220000000 2193.152100000000 3369.459960000000 0.000000000000 1399.681640000000 -1362.772220000000 6676.896970000000 3491.322270000000 2206.573000000000 -1399.681640000000 0.000000000000 2193.152100000000 3491.322270000000 3701.371830000000 43 49 57 2104.000000000000 0.000000000000 0.000000000000 0.000000000000 3795.088620000000 482.892273000000 0.000000000000 2104.000000000000 0.000000000000 -3795.088620000000 0.000000000000 -2162.479250000000 0.000000000000 0.000000000000 2104.000000000000 -482.892273000000 2162.479250000000 0.000000000000 0.000000000000 -3795.088620000000 -482.892273000000 7472.084470000000 -499.045959000000 3918.044680000000 3795.088620000000 0.000000000000 2162.479250000000 -499.045959000000 9243.453130000000 794.056458000000 482.892273000000 -2162.479250000000 0.000000000000 3918.044680000000 794.056458000000 2835.906490000000 43 53 57 2285.000000000000 0.000000000000 0.000000000000 0.000000000000 3783.985840000000 -625.840088000000 0.000000000000 2285.000000000000 0.000000000000 -3783.985840000000 0.000000000000 -2016.192870000000 0.000000000000 0.000000000000 2285.000000000000 625.840088000000 2016.192870000000 0.000000000000 0.000000000000 -3783.985840000000 625.840088000000 6716.799800000000 490.450134000000 3487.048100000000 3783.985840000000 0.000000000000 2016.192870000000 490.450134000000 8534.462890000001 -1061.365360000000 -625.840088000000 -2016.192870000000 0.000000000000 3487.048100000000 -1061.365360000000 2382.456050000000 43 55 57 4477.000000000000 0.000000000000 0.000000000000 0.000000000000 6819.840820000000 -1584.573490000000 0.000000000000 4477.000000000000 0.000000000000 -6819.840820000000 0.000000000000 -964.588745000000 0.000000000000 0.000000000000 4477.000000000000 1584.573490000000 964.588745000000 0.000000000000 0.000000000000 -6819.840820000000 1584.573490000000 11277.450199999999 257.137115000000 1682.313600000000 6819.840820000000 0.000000000000 964.588745000000 257.137115000000 11752.191400000000 -2451.728760000000 -1584.573490000000 -964.588745000000 0.000000000000 1682.313600000000 -2451.728760000000 1901.634640000000 44 45 57 1268.000000000000 0.000000000000 0.000000000000 0.000000000000 1597.446170000000 -968.020874000000 0.000000000000 1268.000000000000 0.000000000000 -1597.446170000000 0.000000000000 739.000000000000 0.000000000000 0.000000000000 1268.000000000000 968.020874000000 -739.000000000000 0.000000000000 0.000000000000 -1597.446170000000 968.020874000000 2923.073970000000 -541.217957000000 -982.312439000000 1597.446170000000 0.000000000000 -739.000000000000 -541.217957000000 2662.648930000000 -1199.524540000000 -968.020874000000 739.000000000000 0.000000000000 -982.312439000000 -1199.524540000000 1254.739750000000 44 47 57 722.000000000000 0.000000000000 0.000000000000 0.000000000000 1082.296140000000 -613.115173000000 0.000000000000 722.000000000000 0.000000000000 -1082.296140000000 0.000000000000 355.303101000000 0.000000000000 0.000000000000 722.000000000000 613.115173000000 -355.303101000000 0.000000000000 0.000000000000 -1082.296140000000 613.115173000000 2251.590580000000 -262.046722000000 -504.837372000000 1082.296140000000 0.000000000000 -355.303101000000 -262.046722000000 1914.517090000000 -940.812500000000 -613.115173000000 355.303101000000 0.000000000000 -504.837372000000 -940.812500000000 786.307983000000 44 52 57 2065.000000000000 0.000000000000 0.000000000000 0.000000000000 3558.651860000000 -870.672791000000 0.000000000000 2065.000000000000 0.000000000000 -3558.651860000000 0.000000000000 -1450.567630000000 0.000000000000 0.000000000000 2065.000000000000 870.672791000000 1450.567630000000 0.000000000000 0.000000000000 -3558.651860000000 870.672791000000 6638.055180000000 596.866821000000 2491.769290000000 3558.651860000000 0.000000000000 1450.567630000000 596.866821000000 7206.444820000000 -1500.420650000000 -870.672791000000 -1450.567630000000 0.000000000000 2491.769290000000 -1500.420650000000 1576.350220000000 45 46 57 2289.000000000000 0.000000000000 0.000000000000 0.000000000000 1788.463750000000 -103.154228000000 0.000000000000 2289.000000000000 0.000000000000 -1788.463750000000 0.000000000000 1099.170410000000 0.000000000000 0.000000000000 2289.000000000000 103.154228000000 -1099.170410000000 0.000000000000 0.000000000000 -1788.463750000000 103.154228000000 1469.538450000000 -31.003206300000 -834.732117000000 1788.463750000000 0.000000000000 -1099.170410000000 -31.003206300000 2020.311040000000 -76.095474200000 -103.154228000000 1099.170410000000 0.000000000000 -834.732117000000 -76.095474200000 617.222046000000 47 48 57 865.000000000000 0.000000000000 0.000000000000 0.000000000000 566.405884000000 -613.846252000000 0.000000000000 865.000000000000 0.000000000000 -566.405884000000 0.000000000000 -1100.304200000000 0.000000000000 0.000000000000 865.000000000000 613.846252000000 1100.304200000000 0.000000000000 0.000000000000 -566.405884000000 613.846252000000 944.019104000000 780.378418000000 721.898254000000 566.405884000000 0.000000000000 1100.304200000000 780.378418000000 1792.132810000000 -377.568359000000 -613.846252000000 -1100.304200000000 0.000000000000 721.898254000000 -377.568359000000 1973.321410000000 47 56 57 1032.000000000000 0.000000000000 0.000000000000 0.000000000000 887.537537000000 30.424713100000 0.000000000000 1032.000000000000 0.000000000000 -887.537537000000 0.000000000000 196.346008000000 0.000000000000 0.000000000000 1032.000000000000 -30.424713100000 -196.346008000000 0.000000000000 0.000000000000 -887.537537000000 -30.424713100000 791.795410000000 1.954351310000 -162.578003000000 887.537537000000 0.000000000000 -196.346008000000 1.954351310000 818.237671000000 31.118555100000 30.424713100000 196.346008000000 0.000000000000 -162.578003000000 31.118555100000 63.479869800000 48 49 57 2045.000000000000 0.000000000000 0.000000000000 0.000000000000 2427.163330000000 -1954.199710000000 0.000000000000 2045.000000000000 0.000000000000 -2427.163330000000 0.000000000000 -2172.751460000000 0.000000000000 0.000000000000 2045.000000000000 1954.199710000000 2172.751460000000 0.000000000000 0.000000000000 -2427.163330000000 1954.199710000000 4857.617190000000 2100.084470000000 2578.437990000000 2427.163330000000 0.000000000000 2172.751460000000 2100.084470000000 5235.989750000000 -2307.199460000000 -1954.199710000000 -2172.751460000000 0.000000000000 2578.437990000000 -2307.199460000000 4322.412110000000 49 54 57 3080.000000000000 0.000000000000 0.000000000000 0.000000000000 4450.331050000000 -371.147278000000 0.000000000000 3080.000000000000 0.000000000000 -4450.331050000000 0.000000000000 -3144.192380000000 0.000000000000 0.000000000000 3080.000000000000 371.147278000000 3144.192380000000 0.000000000000 0.000000000000 -4450.331050000000 371.147278000000 6775.800780000000 420.223114000000 4554.212400000000 4450.331050000000 0.000000000000 3144.192380000000 420.223114000000 9771.140630000000 -609.158142000000 -371.147278000000 -3144.192380000000 0.000000000000 4554.212400000000 -609.158142000000 3530.161130000000 50 55 57 1775.000000000000 0.000000000000 0.000000000000 0.000000000000 2168.087650000000 -420.585236000000 0.000000000000 1775.000000000000 0.000000000000 -2168.087650000000 0.000000000000 -712.092651000000 0.000000000000 0.000000000000 1775.000000000000 420.585236000000 712.092651000000 0.000000000000 0.000000000000 -2168.087650000000 420.585236000000 3160.775630000000 240.522079000000 1007.775820000000 2168.087650000000 0.000000000000 712.092651000000 240.522079000000 3407.539060000000 -639.318665000000 -420.585236000000 -712.092651000000 0.000000000000 1007.775820000000 -639.318665000000 598.638062000000 51 55 57 1960.000000000000 0.000000000000 0.000000000000 0.000000000000 3093.954100000000 -2370.892090000000 0.000000000000 1960.000000000000 0.000000000000 -3093.954100000000 0.000000000000 -829.975647000000 0.000000000000 0.000000000000 1960.000000000000 2370.892090000000 829.975647000000 0.000000000000 0.000000000000 -3093.954100000000 2370.892090000000 7905.124510000000 963.475037000000 1348.000120000000 3093.954100000000 0.000000000000 829.975647000000 963.475037000000 5419.405270000000 -3774.426270000000 -2370.892090000000 -829.975647000000 0.000000000000 1348.000120000000 -3774.426270000000 3419.959720000000 52 53 57 1744.000000000000 0.000000000000 0.000000000000 0.000000000000 2670.542720000000 -1020.247250000000 0.000000000000 1744.000000000000 0.000000000000 -2670.542720000000 0.000000000000 -1574.751710000000 0.000000000000 0.000000000000 1744.000000000000 1020.247250000000 1574.751710000000 0.000000000000 0.000000000000 -2670.542720000000 1020.247250000000 4719.041500000000 931.828247000000 2400.315670000000 2670.542720000000 0.000000000000 1574.751710000000 931.828247000000 5542.496090000000 -1562.004520000000 -1020.247250000000 -1574.751710000000 0.000000000000 2400.315670000000 -1562.004520000000 2071.464360000000 52 54 57 2728.000000000000 0.000000000000 0.000000000000 0.000000000000 4012.652100000000 -1098.874510000000 0.000000000000 2728.000000000000 0.000000000000 -4012.652100000000 0.000000000000 -2591.560790000000 0.000000000000 0.000000000000 2728.000000000000 1098.874510000000 2591.560790000000 0.000000000000 0.000000000000 -4012.652100000000 1098.874510000000 6575.887700000000 1046.775150000000 3806.653560000000 4012.652100000000 0.000000000000 2591.560790000000 1046.775150000000 8385.835940000001 -1655.934200000000 -1098.874510000000 -2591.560790000000 0.000000000000 3806.653560000000 -1655.934200000000 3136.853760000000 54 55 57 2683.000000000000 0.000000000000 0.000000000000 0.000000000000 4640.911620000000 -1313.375000000000 0.000000000000 2683.000000000000 0.000000000000 -4640.911620000000 0.000000000000 -383.631348000000 0.000000000000 0.000000000000 2683.000000000000 1313.375000000000 383.631348000000 0.000000000000 0.000000000000 -4640.911620000000 1313.375000000000 9700.984380000000 350.763458000000 1278.069090000000 4640.911620000000 0.000000000000 383.631348000000 350.763458000000 10154.009800000000 -2488.749510000000 -1313.375000000000 -383.631348000000 0.000000000000 1278.069090000000 -2488.749510000000 1937.756840000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-hotel_umd-maryland_hotel3/gt.info ================================================ 0 11 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14755.747100000001 -1158.123660000000 0.000000000000 5000.000000000000 0.000000000000 -14755.747100000001 0.000000000000 -5518.473630000000 0.000000000000 0.000000000000 5000.000000000000 1158.123660000000 5518.473630000000 0.000000000000 0.000000000000 -14755.747100000001 1158.123660000000 45656.027300000002 922.028931000000 16612.228500000001 14755.747100000001 0.000000000000 5518.473630000000 922.028931000000 50920.027300000002 -2742.854490000000 -1158.123660000000 -5518.473630000000 0.000000000000 16612.228500000001 -2742.854490000000 7890.167480000000 0 27 37 4911.000000000000 0.000000000000 0.000000000000 0.000000000000 14689.044900000001 870.541138000000 0.000000000000 4911.000000000000 0.000000000000 -14689.044900000001 0.000000000000 -3286.318120000000 0.000000000000 0.000000000000 4911.000000000000 -870.541138000000 3286.318120000000 0.000000000000 0.000000000000 -14689.044900000001 -870.541138000000 44679.238299999997 -570.612427000000 10044.853499999999 14689.044900000001 0.000000000000 3286.318120000000 -570.612427000000 46711.105499999998 2570.369140000000 870.541138000000 -3286.318120000000 0.000000000000 10044.853499999999 2570.369140000000 3317.349370000000 1 11 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13332.070299999999 -2985.895510000000 0.000000000000 5000.000000000000 0.000000000000 -13332.070299999999 0.000000000000 -5506.706540000000 0.000000000000 0.000000000000 5000.000000000000 2985.895510000000 5506.706540000000 0.000000000000 0.000000000000 -13332.070299999999 2985.895510000000 38287.429700000001 3216.162840000000 14774.610400000000 13332.070299999999 0.000000000000 5506.706540000000 3216.162840000000 41910.093800000002 -7720.782710000000 -2985.895510000000 -5506.706540000000 0.000000000000 14774.610400000000 -7720.782710000000 8802.703130000000 1 12 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12974.891600000001 -1209.395390000000 0.000000000000 5000.000000000000 0.000000000000 -12974.891600000001 0.000000000000 -5195.797360000000 0.000000000000 0.000000000000 5000.000000000000 1209.395390000000 5195.797360000000 0.000000000000 0.000000000000 -12974.891600000001 1209.395390000000 36595.203099999999 1047.752080000000 13629.839800000000 12974.891600000001 0.000000000000 5195.797360000000 1047.752080000000 39564.343800000002 -3047.176270000000 -1209.395390000000 -5195.797360000000 0.000000000000 13629.839800000000 -3047.176270000000 8267.388670000000 1 13 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12917.399400000000 -3280.130130000000 0.000000000000 5000.000000000000 0.000000000000 -12917.399400000000 0.000000000000 -4677.695310000000 0.000000000000 0.000000000000 5000.000000000000 3280.130130000000 4677.695310000000 0.000000000000 0.000000000000 -12917.399400000000 3280.130130000000 36808.058599999997 2903.270020000000 12247.915999999999 12917.399400000000 0.000000000000 4677.695310000000 2903.270020000000 38315.828099999999 -8067.267580000000 -3280.130130000000 -4677.695310000000 0.000000000000 12247.915999999999 -8067.267580000000 7796.960940000000 3 5 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9466.250980000001 -508.484100000000 0.000000000000 5000.000000000000 0.000000000000 -9466.250980000001 0.000000000000 3878.316410000000 0.000000000000 0.000000000000 5000.000000000000 508.484100000000 -3878.316410000000 0.000000000000 0.000000000000 -9466.250980000001 508.484100000000 19843.566400000000 -95.646987900000 -7046.782710000000 9466.250980000001 0.000000000000 -3878.316410000000 -95.646987900000 22441.669900000001 -1045.789430000000 -508.484100000000 3878.316410000000 0.000000000000 -7046.782710000000 -1045.789430000000 4279.860350000000 5 7 37 4595.000000000000 0.000000000000 0.000000000000 0.000000000000 6613.881350000000 -2829.627930000000 0.000000000000 4595.000000000000 0.000000000000 -6613.881350000000 0.000000000000 4782.536620000000 0.000000000000 0.000000000000 4595.000000000000 2829.627930000000 -4782.536620000000 0.000000000000 0.000000000000 -6613.881350000000 2829.627930000000 11786.404300000000 -2922.120360000000 -6892.126950000000 6613.881350000000 0.000000000000 -4782.536620000000 -2922.120360000000 14881.549800000001 -4131.701170000000 -2829.627930000000 4782.536620000000 0.000000000000 -6892.126950000000 -4131.701170000000 7151.882320000000 8 14 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12342.368200000001 -1958.483030000000 0.000000000000 5000.000000000000 0.000000000000 -12342.368200000001 0.000000000000 4059.545650000000 0.000000000000 0.000000000000 5000.000000000000 1958.483030000000 -4059.545650000000 0.000000000000 0.000000000000 -12342.368200000001 1958.483030000000 31579.386699999999 -1564.926030000000 -10116.831099999999 12342.368200000001 0.000000000000 -4059.545650000000 -1564.926030000000 34549.105499999998 -4759.596680000000 -1958.483030000000 4059.545650000000 0.000000000000 -10116.831099999999 -4759.596680000000 4848.106450000000 8 16 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13755.095700000000 2136.778320000000 0.000000000000 5000.000000000000 0.000000000000 -13755.095700000000 0.000000000000 5222.173340000000 0.000000000000 0.000000000000 5000.000000000000 -2136.778320000000 -5222.173340000000 0.000000000000 0.000000000000 -13755.095700000000 -2136.778320000000 39649.628900000003 2213.227050000000 -14293.858399999999 13755.095700000000 0.000000000000 -5222.173340000000 2213.227050000000 43769.019500000002 5653.737790000000 2136.778320000000 5222.173340000000 0.000000000000 -14293.858399999999 5653.737790000000 7192.283200000000 9 10 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12842.276400000001 -5422.087890000000 0.000000000000 5000.000000000000 0.000000000000 -12842.276400000001 0.000000000000 3988.702150000000 0.000000000000 0.000000000000 5000.000000000000 5422.087890000000 -3988.702150000000 0.000000000000 0.000000000000 -12842.276400000001 5422.087890000000 42314.195299999999 -4214.064940000000 -10153.555700000001 12842.276400000001 0.000000000000 -3988.702150000000 -4214.064940000000 40087.687500000000 -14048.280300000000 -5422.087890000000 3988.702150000000 0.000000000000 -10153.555700000001 -14048.280300000000 10180.828100000001 9 15 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12077.716800000000 -5364.940430000000 0.000000000000 5000.000000000000 0.000000000000 -12077.716800000000 0.000000000000 -1801.679570000000 0.000000000000 0.000000000000 5000.000000000000 5364.940430000000 1801.679570000000 0.000000000000 0.000000000000 -12077.716800000000 5364.940430000000 35537.640599999999 1875.444340000000 4286.756350000000 12077.716800000000 0.000000000000 1801.679570000000 1875.444340000000 30318.687500000000 -12831.189500000000 -5364.940430000000 -1801.679570000000 0.000000000000 4286.756350000000 -12831.189500000000 6901.122070000000 9 16 37 3341.000000000000 0.000000000000 0.000000000000 0.000000000000 9178.837890000001 -3955.946780000000 0.000000000000 3341.000000000000 0.000000000000 -9178.837890000001 0.000000000000 1135.357300000000 0.000000000000 0.000000000000 3341.000000000000 3955.946780000000 -1135.357300000000 0.000000000000 0.000000000000 -9178.837890000001 3955.946780000000 30441.724600000001 -1453.272950000000 -3578.924070000000 9178.837890000001 0.000000000000 -1135.357300000000 -1453.272950000000 27052.013700000000 -10897.280300000000 -3955.946780000000 1135.357300000000 0.000000000000 -3578.924070000000 -10897.280300000000 6271.271970000000 10 11 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8772.749019999999 1854.028080000000 0.000000000000 5000.000000000000 0.000000000000 -8772.749019999999 0.000000000000 5325.496580000000 0.000000000000 0.000000000000 5000.000000000000 -1854.028080000000 -5325.496580000000 0.000000000000 0.000000000000 -8772.749019999999 -1854.028080000000 17526.294900000001 2155.841310000000 -9353.026370000000 8772.749019999999 0.000000000000 -5325.496580000000 2155.841310000000 22176.691400000000 3729.605960000000 1854.028080000000 5325.496580000000 0.000000000000 -9353.026370000000 3729.605960000000 7522.350590000000 10 13 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7719.412110000000 317.536072000000 0.000000000000 5000.000000000000 0.000000000000 -7719.412110000000 0.000000000000 4822.295410000000 0.000000000000 0.000000000000 5000.000000000000 -317.536072000000 -4822.295410000000 0.000000000000 0.000000000000 -7719.412110000000 -317.536072000000 12740.215800000000 315.360596000000 -7147.509770000000 7719.412110000000 0.000000000000 -4822.295410000000 315.360596000000 17742.267599999999 722.267517000000 317.536072000000 4822.295410000000 0.000000000000 -7147.509770000000 722.267517000000 5426.712890000000 10 17 37 4010.000000000000 0.000000000000 0.000000000000 0.000000000000 11913.751000000000 2166.342040000000 0.000000000000 4010.000000000000 0.000000000000 -11913.751000000000 0.000000000000 -639.421326000000 0.000000000000 0.000000000000 4010.000000000000 -2166.342040000000 639.421326000000 0.000000000000 0.000000000000 -11913.751000000000 -2166.342040000000 37563.257799999999 -852.386963000000 1752.804440000000 11913.751000000000 0.000000000000 639.421326000000 -852.386963000000 36468.261700000003 6317.666990000000 2166.342040000000 -639.421326000000 0.000000000000 1752.804440000000 6317.666990000000 2712.767820000000 11 14 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10263.246100000000 739.181030000000 0.000000000000 5000.000000000000 0.000000000000 -10263.246100000000 0.000000000000 -2475.047850000000 0.000000000000 0.000000000000 5000.000000000000 -739.181030000000 2475.047850000000 0.000000000000 0.000000000000 -10263.246100000000 -739.181030000000 22218.648399999998 -84.356964100000 4984.530270000000 10263.246100000000 0.000000000000 2475.047850000000 -84.356964100000 23471.683600000000 1758.900150000000 739.181030000000 -2475.047850000000 0.000000000000 4984.530270000000 1758.900150000000 2820.732180000000 11 27 37 4029.000000000000 0.000000000000 0.000000000000 0.000000000000 6807.636720000000 2802.117190000000 0.000000000000 4029.000000000000 0.000000000000 -6807.636720000000 0.000000000000 4319.017580000000 0.000000000000 0.000000000000 4029.000000000000 -2802.117190000000 -4319.017580000000 0.000000000000 0.000000000000 -6807.636720000000 -2802.117190000000 14222.717800000000 2724.905030000000 -7005.632810000000 6807.636720000000 0.000000000000 -4319.017580000000 2724.905030000000 16946.089800000002 4797.324710000000 2802.117190000000 4319.017580000000 0.000000000000 -7005.632810000000 4797.324710000000 7591.533690000000 12 27 37 4672.000000000000 0.000000000000 0.000000000000 0.000000000000 11278.183600000000 571.919922000000 0.000000000000 4672.000000000000 0.000000000000 -11278.183600000000 0.000000000000 431.283813000000 0.000000000000 0.000000000000 4672.000000000000 -571.919922000000 -431.283813000000 0.000000000000 0.000000000000 -11278.183600000000 -571.919922000000 28184.043000000001 -785.694702000000 -911.587463000000 11278.183600000000 0.000000000000 -431.283813000000 -785.694702000000 29487.041000000001 1392.875730000000 571.919922000000 431.283813000000 0.000000000000 -911.587463000000 1392.875730000000 2970.918700000000 13 14 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7584.627930000000 -4413.166500000000 0.000000000000 5000.000000000000 0.000000000000 -7584.627930000000 0.000000000000 -4640.748050000000 0.000000000000 0.000000000000 5000.000000000000 4413.166500000000 4640.748050000000 0.000000000000 0.000000000000 -7584.627930000000 4413.166500000000 17634.127000000000 4315.185060000000 7303.850590000000 7584.627930000000 0.000000000000 4640.748050000000 4315.185060000000 18033.802700000000 -6156.078610000000 -4413.166500000000 -4640.748050000000 0.000000000000 7303.850590000000 -6156.078610000000 9284.222659999999 13 27 37 4272.000000000000 0.000000000000 0.000000000000 0.000000000000 11468.169900000001 420.310425000000 0.000000000000 4272.000000000000 0.000000000000 -11468.169900000001 0.000000000000 -364.413269000000 0.000000000000 0.000000000000 4272.000000000000 -420.310425000000 364.413269000000 0.000000000000 0.000000000000 -11468.169900000001 -420.310425000000 31240.289100000002 -92.316139200000 1171.745730000000 11468.169900000001 0.000000000000 364.413269000000 -92.316139200000 31569.943400000000 1124.536010000000 420.310425000000 -364.413269000000 0.000000000000 1171.745730000000 1124.536010000000 1086.024540000000 14 16 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12529.182600000000 -1190.006590000000 0.000000000000 5000.000000000000 0.000000000000 -12529.182600000000 0.000000000000 -5834.291020000000 0.000000000000 0.000000000000 5000.000000000000 1190.006590000000 5834.291020000000 0.000000000000 0.000000000000 -12529.182600000000 1190.006590000000 33322.902300000002 1631.368160000000 14547.773400000000 12529.182600000000 0.000000000000 5834.291020000000 1631.368160000000 39683.214800000002 -2706.568360000000 -1190.006590000000 -5834.291020000000 0.000000000000 14547.773400000000 -2706.568360000000 8031.406740000000 14 17 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13361.473599999999 -1066.070070000000 0.000000000000 5000.000000000000 0.000000000000 -13361.473599999999 0.000000000000 -5462.295410000000 0.000000000000 0.000000000000 5000.000000000000 1066.070070000000 5462.295410000000 0.000000000000 0.000000000000 -13361.473599999999 1066.070070000000 36755.886700000003 1235.008420000000 14715.335900000000 13361.473599999999 0.000000000000 5462.295410000000 1235.008420000000 42414.312500000000 -2696.039550000000 -1066.070070000000 -5462.295410000000 0.000000000000 14715.335900000000 -2696.039550000000 7013.676760000000 16 18 37 3548.000000000000 0.000000000000 0.000000000000 0.000000000000 9627.565430000001 2435.469970000000 0.000000000000 3548.000000000000 0.000000000000 -9627.565430000001 0.000000000000 3933.905270000000 0.000000000000 0.000000000000 3548.000000000000 -2435.469970000000 -3933.905270000000 0.000000000000 0.000000000000 -9627.565430000001 -2435.469970000000 28907.752000000000 2708.296630000000 -11155.493200000001 9627.565430000001 0.000000000000 -3933.905270000000 2708.296630000000 31666.656299999999 6474.979490000000 2435.469970000000 3933.905270000000 0.000000000000 -11155.493200000001 6474.979490000000 6678.229980000000 16 19 37 3567.000000000000 0.000000000000 0.000000000000 0.000000000000 10300.639600000000 1506.088620000000 0.000000000000 3567.000000000000 0.000000000000 -10300.639600000000 0.000000000000 4578.125980000000 0.000000000000 0.000000000000 3567.000000000000 -1506.088620000000 -4578.125980000000 0.000000000000 0.000000000000 -10300.639600000000 -1506.088620000000 31185.416000000001 1822.438480000000 -13343.114299999999 10300.639600000000 0.000000000000 -4578.125980000000 1822.438480000000 36072.066400000003 4240.544920000000 1506.088620000000 4578.125980000000 0.000000000000 -13343.114299999999 4240.544920000000 7142.982910000000 18 20 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11886.516600000001 -1568.019900000000 0.000000000000 5000.000000000000 0.000000000000 -11886.516600000001 0.000000000000 2061.218510000000 0.000000000000 0.000000000000 5000.000000000000 1568.019900000000 -2061.218510000000 0.000000000000 0.000000000000 -11886.516600000001 1568.019900000000 29324.734400000001 -495.355865000000 -4668.398930000000 11886.516600000001 0.000000000000 -2061.218510000000 -495.355865000000 29775.699199999999 -3892.155760000000 -1568.019900000000 2061.218510000000 0.000000000000 -4668.398930000000 -3892.155760000000 2148.318600000000 20 33 37 1304.000000000000 0.000000000000 0.000000000000 0.000000000000 2464.824460000000 115.029945000000 0.000000000000 1304.000000000000 0.000000000000 -2464.824460000000 0.000000000000 1197.753540000000 0.000000000000 0.000000000000 1304.000000000000 -115.029945000000 -1197.753540000000 0.000000000000 0.000000000000 -2464.824460000000 -115.029945000000 4951.596190000000 200.011536000000 -2318.576660000000 2464.824460000000 0.000000000000 -1197.753540000000 200.011536000000 6003.085940000000 280.981201000000 115.029945000000 1197.753540000000 0.000000000000 -2318.576660000000 280.981201000000 1336.536990000000 20 34 37 1956.000000000000 0.000000000000 0.000000000000 0.000000000000 3435.957520000000 9.495590210000 0.000000000000 1956.000000000000 0.000000000000 -3435.957520000000 0.000000000000 1712.863890000000 0.000000000000 0.000000000000 1956.000000000000 -9.495590210000 -1712.863890000000 0.000000000000 0.000000000000 -3435.957520000000 -9.495590210000 6476.975100000000 143.472488000000 -3059.230220000000 3435.957520000000 0.000000000000 -1712.863890000000 143.472488000000 7933.177730000000 61.289684300000 9.495590210000 1712.863890000000 0.000000000000 -3059.230220000000 61.289684300000 1901.244380000000 20 36 37 1652.000000000000 0.000000000000 0.000000000000 0.000000000000 2659.956300000000 -315.395905000000 0.000000000000 1652.000000000000 0.000000000000 -2659.956300000000 0.000000000000 68.475311300000 0.000000000000 0.000000000000 1652.000000000000 315.395905000000 -68.475311300000 0.000000000000 0.000000000000 -2659.956300000000 315.395905000000 4784.263670000000 323.781464000000 96.598175000000 2659.956300000000 0.000000000000 -68.475311300000 323.781464000000 4882.252930000000 -687.539795000000 -315.395905000000 68.475311300000 0.000000000000 96.598175000000 -687.539795000000 795.380005000000 21 24 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8093.275390000000 3175.108150000000 0.000000000000 5000.000000000000 0.000000000000 -8093.275390000000 0.000000000000 3567.559080000000 0.000000000000 0.000000000000 5000.000000000000 -3175.108150000000 -3567.559080000000 0.000000000000 0.000000000000 -8093.275390000000 -3175.108150000000 17091.687500000000 2384.408200000000 -5775.754880000000 8093.275390000000 0.000000000000 -3567.559080000000 2384.408200000000 17047.824199999999 5371.145510000000 3175.108150000000 3567.559080000000 0.000000000000 -5775.754880000000 5371.145510000000 5485.768070000000 21 29 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10392.293900000001 5750.167970000000 0.000000000000 5000.000000000000 0.000000000000 -10392.293900000001 0.000000000000 171.155090000000 0.000000000000 0.000000000000 5000.000000000000 -5750.167970000000 -171.155090000000 0.000000000000 0.000000000000 -10392.293900000001 -5750.167970000000 28791.609400000001 322.792542000000 -115.209785000000 10392.293900000001 0.000000000000 -171.155090000000 322.792542000000 22580.494100000000 11752.972700000000 5750.167970000000 171.155090000000 0.000000000000 -115.209785000000 11752.972700000000 7710.813960000000 21 30 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11075.116200000000 4749.483890000000 0.000000000000 5000.000000000000 0.000000000000 -11075.116200000000 0.000000000000 -1506.738040000000 0.000000000000 0.000000000000 5000.000000000000 -4749.483890000000 1506.738040000000 0.000000000000 0.000000000000 -11075.116200000000 -4749.483890000000 29813.322300000000 -1269.910160000000 3574.733400000000 11075.116200000000 0.000000000000 1506.738040000000 -1269.910160000000 25728.884800000000 10305.471700000000 4749.483890000000 -1506.738040000000 0.000000000000 3574.733400000000 10305.471700000000 6021.076170000000 21 31 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11835.289100000000 2598.966800000000 0.000000000000 5000.000000000000 0.000000000000 -11835.289100000000 0.000000000000 -2297.908690000000 0.000000000000 0.000000000000 5000.000000000000 -2598.966800000000 2297.908690000000 0.000000000000 0.000000000000 -11835.289100000000 -2598.966800000000 30375.802700000000 -1057.436890000000 5608.849120000000 11835.289100000000 0.000000000000 2297.908690000000 -1057.436890000000 29776.769499999999 6025.464360000000 2598.966800000000 -2297.908690000000 0.000000000000 5608.849120000000 6025.464360000000 3756.056880000000 22 24 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10037.721700000000 68.831138600000 0.000000000000 5000.000000000000 0.000000000000 -10037.721700000000 0.000000000000 1725.214360000000 0.000000000000 0.000000000000 5000.000000000000 -68.831138600000 -1725.214360000000 0.000000000000 0.000000000000 -10037.721700000000 -68.831138600000 21644.109400000001 104.854095000000 -3248.059570000000 10037.721700000000 0.000000000000 -1725.214360000000 104.854095000000 21807.500000000000 178.935013000000 68.831138600000 1725.214360000000 0.000000000000 -3248.059570000000 178.935013000000 1584.280520000000 22 27 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9825.562500000000 1353.135500000000 0.000000000000 5000.000000000000 0.000000000000 -9825.562500000000 0.000000000000 2609.453370000000 0.000000000000 0.000000000000 5000.000000000000 -1353.135500000000 -2609.453370000000 0.000000000000 0.000000000000 -9825.562500000000 -1353.135500000000 21092.507799999999 1006.041260000000 -5327.219730000000 9825.562500000000 0.000000000000 -2609.453370000000 1006.041260000000 21551.421900000001 3149.021730000000 1353.135500000000 2609.453370000000 0.000000000000 -5327.219730000000 3149.021730000000 2821.654050000000 22 30 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10438.660200000000 2418.898440000000 0.000000000000 5000.000000000000 0.000000000000 -10438.660200000000 0.000000000000 -3380.464360000000 0.000000000000 0.000000000000 5000.000000000000 -2418.898440000000 3380.464360000000 0.000000000000 0.000000000000 -10438.660200000000 -2418.898440000000 24513.906299999999 -1565.788820000000 6954.938480000000 10438.660200000000 0.000000000000 3380.464360000000 -1565.788820000000 24807.291000000001 4843.746580000000 2418.898440000000 -3380.464360000000 0.000000000000 6954.938480000000 4843.746580000000 5542.126950000000 22 31 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11123.084000000001 -1948.185550000000 0.000000000000 5000.000000000000 0.000000000000 -11123.084000000001 0.000000000000 -3408.708980000000 0.000000000000 0.000000000000 5000.000000000000 1948.185550000000 3408.708980000000 0.000000000000 0.000000000000 -11123.084000000001 1948.185550000000 26120.669900000001 921.762512000000 7446.724610000000 11123.084000000001 0.000000000000 3408.708980000000 921.762512000000 27827.169900000001 -4473.849120000000 -1948.185550000000 -3408.708980000000 0.000000000000 7446.724610000000 -4473.849120000000 4162.443850000000 23 24 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7505.446780000000 -4827.831540000000 0.000000000000 5000.000000000000 0.000000000000 -7505.446780000000 0.000000000000 2427.673830000000 0.000000000000 0.000000000000 5000.000000000000 4827.831540000000 -2427.673830000000 0.000000000000 0.000000000000 -7505.446780000000 4827.831540000000 16718.136699999999 -2333.706050000000 -3701.266600000000 7505.446780000000 0.000000000000 -2427.673830000000 -2333.706050000000 13443.534200000000 -7241.111820000000 -4827.831540000000 2427.673830000000 0.000000000000 -3701.266600000000 -7241.111820000000 6195.983890000000 23 27 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7059.371580000000 -4540.982910000000 0.000000000000 5000.000000000000 0.000000000000 -7059.371580000000 0.000000000000 2728.682860000000 0.000000000000 0.000000000000 5000.000000000000 4540.982910000000 -2728.682860000000 0.000000000000 0.000000000000 -7059.371580000000 4540.982910000000 15019.282200000000 -2425.756590000000 -4051.324950000000 7059.371580000000 0.000000000000 -2728.682860000000 -2425.756590000000 12312.308600000000 -6323.015630000000 -4540.982910000000 2728.682860000000 0.000000000000 -4051.324950000000 -6323.015630000000 6139.519530000000 24 25 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 5849.465330000000 106.569824000000 0.000000000000 5000.000000000000 0.000000000000 -5849.465330000000 0.000000000000 3311.684810000000 0.000000000000 0.000000000000 5000.000000000000 -106.569824000000 -3311.684810000000 0.000000000000 0.000000000000 -5849.465330000000 -106.569824000000 10550.244100000000 578.423218000000 -4980.363280000000 5849.465330000000 0.000000000000 -3311.684810000000 578.423218000000 12726.620100000000 1381.153320000000 106.569824000000 3311.684810000000 0.000000000000 -4980.363280000000 1381.153320000000 3364.580320000000 24 30 37 180.000000000000 0.000000000000 0.000000000000 0.000000000000 292.136597000000 -25.611816400000 0.000000000000 180.000000000000 0.000000000000 -292.136597000000 0.000000000000 -112.202393000000 0.000000000000 0.000000000000 180.000000000000 25.611816400000 112.202393000000 0.000000000000 0.000000000000 -292.136597000000 25.611816400000 500.103271000000 15.684609400000 181.664993000000 292.136597000000 0.000000000000 112.202393000000 15.684609400000 550.898560000000 -49.499954200000 -25.611816400000 -112.202393000000 0.000000000000 181.664993000000 -49.499954200000 91.710289000000 25 26 37 3791.000000000000 0.000000000000 0.000000000000 0.000000000000 2921.557370000000 1550.089480000000 0.000000000000 3791.000000000000 0.000000000000 -2921.557370000000 0.000000000000 479.933441000000 0.000000000000 0.000000000000 3791.000000000000 -1550.089480000000 -479.933441000000 0.000000000000 0.000000000000 -2921.557370000000 -1550.089480000000 3017.637940000000 180.829849000000 -350.716766000000 2921.557370000000 0.000000000000 -479.933441000000 180.829849000000 2479.871830000000 1155.396000000000 1550.089480000000 479.933441000000 0.000000000000 -350.716766000000 1155.396000000000 860.833252000000 25 28 37 4194.000000000000 0.000000000000 0.000000000000 0.000000000000 4075.602540000000 -130.504211000000 0.000000000000 4194.000000000000 0.000000000000 -4075.602540000000 0.000000000000 -1173.067750000000 0.000000000000 0.000000000000 4194.000000000000 130.504211000000 1173.067750000000 0.000000000000 0.000000000000 -4075.602540000000 130.504211000000 4421.915040000000 -60.475231200000 1361.090580000000 4075.602540000000 0.000000000000 1173.067750000000 -60.475231200000 4834.142580000000 39.842384300000 -130.504211000000 -1173.067750000000 0.000000000000 1361.090580000000 39.842384300000 680.232910000000 27 28 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 4868.554690000000 -4596.900880000000 0.000000000000 5000.000000000000 0.000000000000 -4868.554690000000 0.000000000000 -2103.497560000000 0.000000000000 0.000000000000 5000.000000000000 4596.900880000000 2103.497560000000 0.000000000000 0.000000000000 -4868.554690000000 4596.900880000000 9390.416990000000 1995.728390000000 2278.124760000000 4868.554690000000 0.000000000000 2103.497560000000 1995.728390000000 6490.233400000000 -4518.928710000000 -4596.900880000000 -2103.497560000000 0.000000000000 2278.124760000000 -4518.928710000000 5632.998050000000 28 31 37 3392.000000000000 0.000000000000 0.000000000000 0.000000000000 4302.384770000000 -1320.513180000000 0.000000000000 3392.000000000000 0.000000000000 -4302.384770000000 0.000000000000 -3966.459720000000 0.000000000000 0.000000000000 3392.000000000000 1320.513180000000 3966.459720000000 0.000000000000 0.000000000000 -4302.384770000000 1320.513180000000 6244.183110000000 1510.467650000000 5024.605470000000 4302.384770000000 0.000000000000 3966.459720000000 1510.467650000000 10345.873000000000 -1709.695190000000 -1320.513180000000 -3966.459720000000 0.000000000000 5024.605470000000 -1709.695190000000 5267.606930000000 29 31 37 3908.000000000000 0.000000000000 0.000000000000 0.000000000000 5951.574220000000 -805.517639000000 0.000000000000 3908.000000000000 0.000000000000 -5951.574220000000 0.000000000000 -2677.108400000000 0.000000000000 0.000000000000 3908.000000000000 805.517639000000 2677.108400000000 0.000000000000 0.000000000000 -5951.574220000000 805.517639000000 9774.519530000000 272.822601000000 3922.778320000000 5951.574220000000 0.000000000000 2677.108400000000 272.822601000000 11493.848599999999 -1417.274660000000 -805.517639000000 -2677.108400000000 0.000000000000 3922.778320000000 -1417.274660000000 2809.919190000000 30 32 37 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8242.427729999999 -4679.182620000000 0.000000000000 5000.000000000000 0.000000000000 -8242.427729999999 0.000000000000 -4847.832520000000 0.000000000000 0.000000000000 5000.000000000000 4679.182620000000 4847.832520000000 0.000000000000 0.000000000000 -8242.427729999999 4679.182620000000 18621.929700000001 4679.078130000000 8014.309080000000 8242.427729999999 0.000000000000 4847.832520000000 4679.078130000000 18598.236300000000 -7727.742680000000 -4679.182620000000 -4847.832520000000 0.000000000000 8014.309080000000 -7727.742680000000 9981.988280000000 30 33 37 1647.000000000000 0.000000000000 0.000000000000 0.000000000000 2353.413090000000 -1846.982790000000 0.000000000000 1647.000000000000 0.000000000000 -2353.413090000000 0.000000000000 -1888.080320000000 0.000000000000 0.000000000000 1647.000000000000 1846.982790000000 1888.080320000000 0.000000000000 0.000000000000 -2353.413090000000 1846.982790000000 5778.554200000000 2135.295900000000 2775.575930000000 2353.413090000000 0.000000000000 1888.080320000000 2135.295900000000 5730.104490000000 -2576.384030000000 -1846.982790000000 -1888.080320000000 0.000000000000 2775.575930000000 -2576.384030000000 4551.314940000000 31 35 37 2729.000000000000 0.000000000000 0.000000000000 0.000000000000 2757.331540000000 875.710999000000 0.000000000000 2729.000000000000 0.000000000000 -2757.331540000000 0.000000000000 -3076.288330000000 0.000000000000 0.000000000000 2729.000000000000 -875.710999000000 3076.288330000000 0.000000000000 0.000000000000 -2757.331540000000 -875.710999000000 3317.868650000000 -964.052002000000 3101.969240000000 2757.331540000000 0.000000000000 3076.288330000000 -964.052002000000 6347.686040000000 802.819702000000 875.710999000000 -3076.288330000000 0.000000000000 3101.969240000000 802.819702000000 3931.324220000000 31 36 37 4022.000000000000 0.000000000000 0.000000000000 0.000000000000 4150.331050000000 1275.703860000000 0.000000000000 4022.000000000000 0.000000000000 -4150.331050000000 0.000000000000 -4478.655270000000 0.000000000000 0.000000000000 4022.000000000000 -1275.703860000000 4478.655270000000 0.000000000000 0.000000000000 -4150.331050000000 -1275.703860000000 5300.633300000000 -1367.562620000000 4611.408690000000 4150.331050000000 0.000000000000 4478.655270000000 -1367.562620000000 9485.794920000000 1114.893310000000 1275.703860000000 -4478.655270000000 0.000000000000 4611.408690000000 1114.893310000000 5853.389160000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-mit_76_studyroom-76-1studyroom2/gt.info ================================================ 0 3 66 4464.000000000000 0.000000000000 0.000000000000 0.000000000000 10732.483399999999 -2437.557370000000 0.000000000000 4464.000000000000 0.000000000000 -10732.483399999999 0.000000000000 3599.064450000000 0.000000000000 0.000000000000 4464.000000000000 2437.557370000000 -3599.064450000000 0.000000000000 0.000000000000 -10732.483399999999 2437.557370000000 27890.738300000001 -1880.912960000000 -8992.965819999999 10732.483399999999 0.000000000000 -3599.064450000000 -1880.912960000000 29691.898399999998 -5721.690920000000 -2437.557370000000 3599.064450000000 0.000000000000 -8992.965819999999 -5721.690920000000 4823.158690000000 0 8 66 4474.000000000000 0.000000000000 0.000000000000 0.000000000000 10882.518599999999 -961.239136000000 0.000000000000 4474.000000000000 0.000000000000 -10882.518599999999 0.000000000000 2471.361080000000 0.000000000000 0.000000000000 4474.000000000000 961.239136000000 -2471.361080000000 0.000000000000 0.000000000000 -10882.518599999999 961.239136000000 27019.168000000001 -723.388489000000 -6155.132810000000 10882.518599999999 0.000000000000 -2471.361080000000 -723.388489000000 28675.371100000000 -2316.007080000000 -961.239136000000 2471.361080000000 0.000000000000 -6155.132810000000 -2316.007080000000 2479.098390000000 0 18 66 3095.000000000000 0.000000000000 0.000000000000 0.000000000000 8761.251950000000 -2066.690190000000 0.000000000000 3095.000000000000 0.000000000000 -8761.251950000000 0.000000000000 -4076.209720000000 0.000000000000 0.000000000000 3095.000000000000 2066.690190000000 4076.209720000000 0.000000000000 0.000000000000 -8761.251950000000 2066.690190000000 26560.142599999999 2710.304690000000 11610.060500000000 8761.251950000000 0.000000000000 4076.209720000000 2710.304690000000 30550.091799999998 -5746.911620000000 -2066.690190000000 -4076.209720000000 0.000000000000 11610.060500000000 -5746.911620000000 6834.172360000000 0 19 66 4854.000000000000 0.000000000000 0.000000000000 0.000000000000 13032.636699999999 -2402.288090000000 0.000000000000 4854.000000000000 0.000000000000 -13032.636699999999 0.000000000000 -4427.922850000000 0.000000000000 0.000000000000 4854.000000000000 2402.288090000000 4427.922850000000 0.000000000000 0.000000000000 -13032.636699999999 2402.288090000000 37500.402300000002 2531.691650000000 12674.553700000000 13032.636699999999 0.000000000000 4427.922850000000 2531.691650000000 41036.894500000002 -6591.131350000000 -2402.288090000000 -4427.922850000000 0.000000000000 12674.553700000000 -6591.131350000000 6484.703610000000 0 21 66 4898.000000000000 0.000000000000 0.000000000000 0.000000000000 11590.284200000000 -1922.691410000000 0.000000000000 4898.000000000000 0.000000000000 -11590.284200000000 0.000000000000 -2441.598880000000 0.000000000000 0.000000000000 4898.000000000000 1922.691410000000 2441.598880000000 0.000000000000 0.000000000000 -11590.284200000000 1922.691410000000 29376.027300000002 1391.386470000000 6474.306150000000 11590.284200000000 0.000000000000 2441.598880000000 1391.386470000000 30863.478500000001 -4589.797360000000 -1922.691410000000 -2441.598880000000 0.000000000000 6474.306150000000 -4589.797360000000 3797.583500000000 0 22 66 1753.000000000000 0.000000000000 0.000000000000 0.000000000000 3664.653320000000 -646.731323000000 0.000000000000 1753.000000000000 0.000000000000 -3664.653320000000 0.000000000000 -684.521057000000 0.000000000000 0.000000000000 1753.000000000000 646.731323000000 684.521057000000 0.000000000000 0.000000000000 -3664.653320000000 646.731323000000 7998.154790000000 235.177902000000 1462.566650000000 3664.653320000000 0.000000000000 684.521057000000 235.177902000000 8073.024900000000 -1323.499020000000 -646.731323000000 -684.521057000000 0.000000000000 1462.566650000000 -1323.499020000000 593.582336000000 0 33 66 2921.000000000000 0.000000000000 0.000000000000 0.000000000000 6060.877930000000 -2095.675290000000 0.000000000000 2921.000000000000 0.000000000000 -6060.877930000000 0.000000000000 -841.665222000000 0.000000000000 0.000000000000 2921.000000000000 2095.675290000000 841.665222000000 0.000000000000 0.000000000000 -6060.877930000000 2095.675290000000 14291.687500000000 629.007629000000 1767.422850000000 6060.877930000000 0.000000000000 841.665222000000 629.007629000000 13169.435500000000 -4384.848140000000 -2095.675290000000 -841.665222000000 0.000000000000 1767.422850000000 -4384.848140000000 2120.902100000000 0 39 66 1405.000000000000 0.000000000000 0.000000000000 0.000000000000 3800.440920000000 -552.248779000000 0.000000000000 1405.000000000000 0.000000000000 -3800.440920000000 0.000000000000 1586.683720000000 0.000000000000 0.000000000000 1405.000000000000 552.248779000000 -1586.683720000000 0.000000000000 0.000000000000 -3800.440920000000 552.248779000000 10601.989299999999 -637.112976000000 -4327.286130000000 3800.440920000000 0.000000000000 -1586.683720000000 -637.112976000000 12186.437500000000 -1518.811400000000 -552.248779000000 1586.683720000000 0.000000000000 -4327.286130000000 -1518.811400000000 2092.059330000000 0 44 66 1865.000000000000 0.000000000000 0.000000000000 0.000000000000 4880.280760000000 -568.552856000000 0.000000000000 1865.000000000000 0.000000000000 -4880.280760000000 0.000000000000 1962.609860000000 0.000000000000 0.000000000000 1865.000000000000 568.552856000000 -1962.609860000000 0.000000000000 0.000000000000 -4880.280760000000 568.552856000000 13118.081099999999 -642.654053000000 -5204.161620000000 4880.280760000000 0.000000000000 -1962.609860000000 -642.654053000000 15027.289100000000 -1537.684330000000 -568.552856000000 1962.609860000000 0.000000000000 -5204.161620000000 -1537.684330000000 2369.222170000000 0 45 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12516.021500000001 -1449.085690000000 0.000000000000 5000.000000000000 0.000000000000 -12516.021500000001 0.000000000000 3835.903320000000 0.000000000000 0.000000000000 5000.000000000000 1449.085690000000 -3835.903320000000 0.000000000000 0.000000000000 -12516.021500000001 1449.085690000000 32185.021499999999 -1257.733030000000 -9835.753909999999 12516.021500000001 0.000000000000 -3835.903320000000 -1257.733030000000 35039.527300000002 -3668.174560000000 -1449.085690000000 3835.903320000000 0.000000000000 -9835.753909999999 -3668.174560000000 4072.383060000000 0 50 66 3915.000000000000 0.000000000000 0.000000000000 0.000000000000 9607.118160000000 -586.546448000000 0.000000000000 3915.000000000000 0.000000000000 -9607.118160000000 0.000000000000 2205.326660000000 0.000000000000 0.000000000000 3915.000000000000 586.546448000000 -2205.326660000000 0.000000000000 0.000000000000 -9607.118160000000 586.546448000000 23894.789100000002 -474.051208000000 -5469.824710000000 9607.118160000000 0.000000000000 -2205.326660000000 -474.051208000000 25382.134800000000 -1427.163820000000 -586.546448000000 2205.326660000000 0.000000000000 -5469.824710000000 -1427.163820000000 1934.123290000000 0 51 66 2887.000000000000 0.000000000000 0.000000000000 0.000000000000 7258.041020000000 -59.625225100000 0.000000000000 2887.000000000000 0.000000000000 -7258.041020000000 0.000000000000 1461.911740000000 0.000000000000 0.000000000000 2887.000000000000 59.625225100000 -1461.911740000000 0.000000000000 0.000000000000 -7258.041020000000 59.625225100000 18329.339800000002 -86.582649200000 -3678.483640000000 7258.041020000000 0.000000000000 -1461.911740000000 -86.582649200000 19250.062500000000 -138.052444000000 -59.625225100000 1461.911740000000 0.000000000000 -3678.483640000000 -138.052444000000 1034.451420000000 0 64 66 4029.000000000000 0.000000000000 0.000000000000 0.000000000000 11329.674800000001 -2740.599370000000 0.000000000000 4029.000000000000 0.000000000000 -11329.674800000001 0.000000000000 -4764.512700000000 0.000000000000 0.000000000000 4029.000000000000 2740.599370000000 4764.512700000000 0.000000000000 0.000000000000 -11329.674800000001 2740.599370000000 34158.660199999998 3236.329590000000 13436.686500000000 11329.674800000001 0.000000000000 4764.512700000000 3236.329590000000 37978.109400000001 -7568.598140000000 -2740.599370000000 -4764.512700000000 0.000000000000 13436.686500000000 -7568.598140000000 7649.607420000000 1 8 66 4738.000000000000 0.000000000000 0.000000000000 0.000000000000 11867.504900000000 -951.499329000000 0.000000000000 4738.000000000000 0.000000000000 -11867.504900000000 0.000000000000 3658.206540000000 0.000000000000 0.000000000000 4738.000000000000 951.499329000000 -3658.206540000000 0.000000000000 0.000000000000 -11867.504900000000 951.499329000000 30394.052700000000 -1060.397580000000 -9471.037109999999 11867.504900000000 0.000000000000 -3658.206540000000 -1060.397580000000 33827.480499999998 -2395.518550000000 -951.499329000000 3658.206540000000 0.000000000000 -9471.037109999999 -2395.518550000000 4331.335450000000 1 19 66 4225.000000000000 0.000000000000 0.000000000000 0.000000000000 10659.821300000000 -2145.428960000000 0.000000000000 4225.000000000000 0.000000000000 -10659.821300000000 0.000000000000 -3858.146730000000 0.000000000000 0.000000000000 4225.000000000000 2145.428960000000 3858.146730000000 0.000000000000 0.000000000000 -10659.821300000000 2145.428960000000 28888.648399999998 2270.072020000000 10406.544900000001 10659.821300000000 0.000000000000 3858.146730000000 2270.072020000000 32068.744100000000 -5558.825680000000 -2145.428960000000 -3858.146730000000 0.000000000000 10406.544900000001 -5558.825680000000 5762.395020000000 1 20 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12751.287100000000 -2526.075930000000 0.000000000000 5000.000000000000 0.000000000000 -12751.287100000000 0.000000000000 -4124.835450000000 0.000000000000 0.000000000000 5000.000000000000 2526.075930000000 4124.835450000000 0.000000000000 0.000000000000 -12751.287100000000 2526.075930000000 34698.402300000002 2442.752200000000 11137.532200000000 12751.287100000000 0.000000000000 4124.835450000000 2442.752200000000 37658.898399999998 -6583.100100000000 -2526.075930000000 -4124.835450000000 0.000000000000 11137.532200000000 -6583.100100000000 5985.795410000000 1 21 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11984.614299999999 -1741.749270000000 0.000000000000 5000.000000000000 0.000000000000 -11984.614299999999 0.000000000000 -2799.971190000000 0.000000000000 0.000000000000 5000.000000000000 1741.749270000000 2799.971190000000 0.000000000000 0.000000000000 -11984.614299999999 1741.749270000000 30241.490200000000 1521.237180000000 7215.577150000000 11984.614299999999 0.000000000000 2799.971190000000 1521.237180000000 32065.382799999999 -4349.152830000000 -1741.749270000000 -2799.971190000000 0.000000000000 7215.577150000000 -4349.152830000000 3763.916750000000 1 22 66 3225.000000000000 0.000000000000 0.000000000000 0.000000000000 6906.360350000000 -753.145813000000 0.000000000000 3225.000000000000 0.000000000000 -6906.360350000000 0.000000000000 -1139.376590000000 0.000000000000 0.000000000000 3225.000000000000 753.145813000000 1139.376590000000 0.000000000000 0.000000000000 -6906.360350000000 753.145813000000 15106.711900000000 263.180267000000 2426.475830000000 6906.360350000000 0.000000000000 1139.376590000000 263.180267000000 15360.608399999999 -1565.803100000000 -753.145813000000 -1139.376590000000 0.000000000000 2426.475830000000 -1565.803100000000 712.441223000000 1 33 66 2583.000000000000 0.000000000000 0.000000000000 0.000000000000 5048.292970000000 -1390.230100000000 0.000000000000 2583.000000000000 0.000000000000 -5048.292970000000 0.000000000000 -338.751953000000 0.000000000000 0.000000000000 2583.000000000000 1390.230100000000 338.751953000000 0.000000000000 0.000000000000 -5048.292970000000 1390.230100000000 10758.645500000001 129.064392000000 617.538940000000 5048.292970000000 0.000000000000 338.751953000000 129.064392000000 10106.625000000000 -2759.907710000000 -1390.230100000000 -338.751953000000 0.000000000000 617.538940000000 -2759.907710000000 978.024902000000 1 39 66 4082.000000000000 0.000000000000 0.000000000000 0.000000000000 11463.828100000001 -1426.416750000000 0.000000000000 4082.000000000000 0.000000000000 -11463.828100000001 0.000000000000 4897.118160000000 0.000000000000 0.000000000000 4082.000000000000 1426.416750000000 -4897.118160000000 0.000000000000 0.000000000000 -11463.828100000001 1426.416750000000 33032.117200000001 -1731.726070000000 -13809.377899999999 11463.828100000001 0.000000000000 -4897.118160000000 -1731.726070000000 38422.410199999998 -3996.619140000000 -1426.416750000000 4897.118160000000 0.000000000000 -13809.377899999999 -3996.619140000000 6564.211910000000 1 44 66 3411.000000000000 0.000000000000 0.000000000000 0.000000000000 9470.916020000001 -903.261536000000 0.000000000000 3411.000000000000 0.000000000000 -9470.916020000001 0.000000000000 4005.589110000000 0.000000000000 0.000000000000 3411.000000000000 903.261536000000 -4005.589110000000 0.000000000000 0.000000000000 -9470.916020000001 903.261536000000 26854.318400000000 -1119.885860000000 -11221.293900000001 9470.916020000001 0.000000000000 -4005.589110000000 -1119.885860000000 31345.476600000002 -2557.886230000000 -903.261536000000 4005.589110000000 0.000000000000 -11221.293900000001 -2557.886230000000 5143.938960000000 1 50 66 4495.000000000000 0.000000000000 0.000000000000 0.000000000000 11518.023400000000 -735.958069000000 0.000000000000 4495.000000000000 0.000000000000 -11518.023400000000 0.000000000000 3629.167240000000 0.000000000000 0.000000000000 4495.000000000000 735.958069000000 -3629.167240000000 0.000000000000 0.000000000000 -11518.023400000000 735.958069000000 30048.060500000000 -927.562622000000 -9592.885740000000 11518.023400000000 0.000000000000 -3629.167240000000 -927.562622000000 33607.480499999998 -1958.369630000000 -735.958069000000 3629.167240000000 0.000000000000 -9592.885740000000 -1958.369630000000 4244.099120000000 1 51 66 2374.000000000000 0.000000000000 0.000000000000 0.000000000000 5993.910640000000 148.791840000000 0.000000000000 2374.000000000000 0.000000000000 -5993.910640000000 0.000000000000 1315.642580000000 0.000000000000 0.000000000000 2374.000000000000 -148.791840000000 -1315.642580000000 0.000000000000 0.000000000000 -5993.910640000000 -148.791840000000 15230.150400000000 12.095636400000 -3372.991210000000 5993.910640000000 0.000000000000 -1315.642580000000 12.095636400000 16241.473599999999 380.430145000000 148.791840000000 1315.642580000000 0.000000000000 -3372.991210000000 380.430145000000 1113.779300000000 1 64 66 3823.000000000000 0.000000000000 0.000000000000 0.000000000000 9973.290040000000 -2660.405030000000 0.000000000000 3823.000000000000 0.000000000000 -9973.290040000000 0.000000000000 -4539.162110000000 0.000000000000 0.000000000000 3823.000000000000 2660.405030000000 4539.162110000000 0.000000000000 0.000000000000 -9973.290040000000 2660.405030000000 28117.863300000001 3137.848140000000 11925.978499999999 9973.290040000000 0.000000000000 4539.162110000000 3137.848140000000 31747.275399999999 -6859.390140000000 -2660.405030000000 -4539.162110000000 0.000000000000 11925.978499999999 -6859.390140000000 7396.366210000000 2 4 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13730.223599999999 -3356.561280000000 0.000000000000 5000.000000000000 0.000000000000 -13730.223599999999 0.000000000000 6380.898930000000 0.000000000000 0.000000000000 5000.000000000000 3356.561280000000 -6380.898930000000 0.000000000000 0.000000000000 -13730.223599999999 3356.561280000000 41144.914100000002 -4214.879880000000 -17576.668000000001 13730.223599999999 0.000000000000 -6380.898930000000 -4214.879880000000 46907.425799999997 -8785.543949999999 -3356.561280000000 6380.898930000000 0.000000000000 -17576.668000000001 -8785.543949999999 10940.683600000000 2 21 66 3622.000000000000 0.000000000000 0.000000000000 0.000000000000 8021.749510000000 -1433.489010000000 0.000000000000 3622.000000000000 0.000000000000 -8021.749510000000 0.000000000000 -2221.483400000000 0.000000000000 0.000000000000 3622.000000000000 1433.489010000000 2221.483400000000 0.000000000000 0.000000000000 -8021.749510000000 1433.489010000000 18658.859400000001 899.831299000000 4857.774410000000 8021.749510000000 0.000000000000 2221.483400000000 899.831299000000 19438.630900000000 -3044.948970000000 -1433.489010000000 -2221.483400000000 0.000000000000 4857.774410000000 -3044.948970000000 2149.472410000000 2 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11682.374000000000 -2701.008300000000 0.000000000000 5000.000000000000 0.000000000000 -11682.374000000000 0.000000000000 -1640.107300000000 0.000000000000 0.000000000000 5000.000000000000 2701.008300000000 1640.107300000000 0.000000000000 0.000000000000 -11682.374000000000 2701.008300000000 29344.314500000000 707.124756000000 3679.465820000000 11682.374000000000 0.000000000000 1640.107300000000 707.124756000000 28490.662100000001 -6287.431640000000 -2701.008300000000 -1640.107300000000 0.000000000000 3679.465820000000 -6287.431640000000 2743.635500000000 2 43 66 2117.000000000000 0.000000000000 0.000000000000 0.000000000000 6162.347660000000 -1250.088010000000 0.000000000000 2117.000000000000 0.000000000000 -6162.347660000000 0.000000000000 2961.128170000000 0.000000000000 0.000000000000 2117.000000000000 1250.088010000000 -2961.128170000000 0.000000000000 0.000000000000 -6162.347660000000 1250.088010000000 18832.505900000000 -1741.638550000000 -8620.614260000000 6162.347660000000 0.000000000000 -2961.128170000000 -1741.638550000000 22163.703099999999 -3611.600340000000 -1250.088010000000 2961.128170000000 0.000000000000 -8620.614260000000 -3611.600340000000 4983.483890000000 2 51 66 3078.000000000000 0.000000000000 0.000000000000 0.000000000000 8260.888670000000 -678.293945000000 0.000000000000 3078.000000000000 0.000000000000 -8260.888670000000 0.000000000000 -507.245911000000 0.000000000000 0.000000000000 3078.000000000000 678.293945000000 507.245911000000 0.000000000000 0.000000000000 -8260.888670000000 678.293945000000 22496.322300000000 48.513568900000 1186.229980000000 8260.888670000000 0.000000000000 507.245911000000 48.513568900000 22727.435500000000 -1835.100590000000 -678.293945000000 -507.245911000000 0.000000000000 1186.229980000000 -1835.100590000000 631.624512000000 3 8 66 3653.000000000000 0.000000000000 0.000000000000 0.000000000000 10929.407200000000 -1766.244630000000 0.000000000000 3653.000000000000 0.000000000000 -10929.407200000000 0.000000000000 -2305.526120000000 0.000000000000 0.000000000000 3653.000000000000 1766.244630000000 2305.526120000000 0.000000000000 0.000000000000 -10929.407200000000 1766.244630000000 34198.621099999997 1063.363400000000 6618.651860000000 10929.407200000000 0.000000000000 2305.526120000000 1063.363400000000 34969.585899999998 -5326.366210000000 -1766.244630000000 -2305.526120000000 0.000000000000 6618.651860000000 -5326.366210000000 2605.321040000000 3 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14477.715800000000 -2918.516600000000 0.000000000000 5000.000000000000 0.000000000000 -14477.715800000000 0.000000000000 -3797.648190000000 0.000000000000 0.000000000000 5000.000000000000 2918.516600000000 3797.648190000000 0.000000000000 0.000000000000 -14477.715800000000 2918.516600000000 44604.199200000003 2198.719240000000 10890.001000000000 14477.715800000000 0.000000000000 3797.648190000000 2198.719240000000 45960.839800000002 -8353.839840000001 -2918.516600000000 -3797.648190000000 0.000000000000 10890.001000000000 -8353.839840000001 4987.741210000000 3 36 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13965.548800000000 -3038.446290000000 0.000000000000 5000.000000000000 0.000000000000 -13965.548800000000 0.000000000000 -3337.038090000000 0.000000000000 0.000000000000 5000.000000000000 3038.446290000000 3337.038090000000 0.000000000000 0.000000000000 -13965.548800000000 3038.446290000000 41737.222699999998 1998.296880000000 9167.121090000001 13965.548800000000 0.000000000000 3337.038090000000 1998.296880000000 42451.195299999999 -8385.170899999999 -3038.446290000000 -3337.038090000000 0.000000000000 9167.121090000001 -8385.170899999999 4667.939940000000 3 37 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14170.790999999999 -2987.066410000000 0.000000000000 5000.000000000000 0.000000000000 -14170.790999999999 0.000000000000 -2988.659420000000 0.000000000000 0.000000000000 5000.000000000000 2987.066410000000 2988.659420000000 0.000000000000 0.000000000000 -14170.790999999999 2987.066410000000 42954.917999999998 1768.575560000000 8238.002930000001 14170.790999999999 0.000000000000 2988.659420000000 1768.575560000000 43362.636700000003 -8338.804690000001 -2987.066410000000 -2988.659420000000 0.000000000000 8238.002930000001 -8338.804690000001 4219.499020000000 3 41 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15946.118200000001 431.402863000000 0.000000000000 5000.000000000000 0.000000000000 -15946.118200000001 0.000000000000 6172.131350000000 0.000000000000 0.000000000000 5000.000000000000 -431.402863000000 -6172.131350000000 0.000000000000 0.000000000000 -15946.118200000001 -431.402863000000 52655.554700000001 765.784363000000 -19678.236300000000 15946.118200000001 0.000000000000 -6172.131350000000 765.784363000000 58831.460899999998 1606.198240000000 431.402863000000 6172.131350000000 0.000000000000 -19678.236300000000 1606.198240000000 9449.872069999999 3 42 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15954.202100000000 616.262878000000 0.000000000000 5000.000000000000 0.000000000000 -15954.202100000000 0.000000000000 6031.415530000000 0.000000000000 0.000000000000 5000.000000000000 -616.262878000000 -6031.415530000000 0.000000000000 0.000000000000 -15954.202100000000 -616.262878000000 52641.296900000001 860.885315000000 -19190.972699999998 15954.202100000000 0.000000000000 -6031.415530000000 860.885315000000 58653.882799999999 2188.189700000000 616.262878000000 6031.415530000000 0.000000000000 -19190.972699999998 2188.189700000000 9149.753909999999 4 6 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15066.319299999999 -3240.307370000000 0.000000000000 5000.000000000000 0.000000000000 -15066.319299999999 0.000000000000 -5261.918950000000 0.000000000000 0.000000000000 5000.000000000000 3240.307370000000 5261.918950000000 0.000000000000 0.000000000000 -15066.319299999999 3240.307370000000 48233.343800000002 3286.577390000000 16017.456099999999 15066.319299999999 0.000000000000 5261.918950000000 3286.577390000000 51837.964800000002 -9496.627930000001 -3240.307370000000 -5261.918950000000 0.000000000000 16017.456099999999 -9496.627930000001 8286.875980000001 4 7 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15879.489299999999 -3105.443120000000 0.000000000000 5000.000000000000 0.000000000000 -15879.489299999999 0.000000000000 -5762.121090000000 0.000000000000 0.000000000000 5000.000000000000 3105.443120000000 5762.121090000000 0.000000000000 0.000000000000 -15879.489299999999 3105.443120000000 52858.808599999997 3564.771730000000 18225.855500000001 15879.489299999999 0.000000000000 5762.121090000000 3564.771730000000 57707.097699999998 -9719.677729999999 -3105.443120000000 -5762.121090000000 0.000000000000 18225.855500000001 -9719.677729999999 9068.471680000001 4 38 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16249.137699999999 -2528.399660000000 0.000000000000 5000.000000000000 0.000000000000 -16249.137699999999 0.000000000000 -5818.150880000000 0.000000000000 0.000000000000 5000.000000000000 2528.399660000000 5818.150880000000 0.000000000000 0.000000000000 -16249.137699999999 2528.399660000000 54567.097699999998 2947.214600000000 18854.685500000000 16249.137699999999 0.000000000000 5818.150880000000 2947.214600000000 60049.664100000002 -8087.287600000000 -2528.399660000000 -5818.150880000000 0.000000000000 18854.685500000000 -8087.287600000000 8579.076170000000 4 45 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16234.798800000000 -2664.177000000000 0.000000000000 5000.000000000000 0.000000000000 -16234.798800000000 0.000000000000 -5399.137700000000 0.000000000000 0.000000000000 5000.000000000000 2664.177000000000 5399.137700000000 0.000000000000 0.000000000000 -16234.798800000000 2664.177000000000 54566.960899999998 2870.602780000000 17498.039100000002 16234.798800000000 0.000000000000 5399.137700000000 2870.602780000000 59053.804700000001 -8534.145510000000 -2664.177000000000 -5399.137700000000 0.000000000000 17498.039100000002 -8534.145510000000 7847.047360000000 4 49 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15214.958000000001 -3281.844730000000 0.000000000000 5000.000000000000 0.000000000000 -15214.958000000001 0.000000000000 -5867.562500000000 0.000000000000 0.000000000000 5000.000000000000 3281.844730000000 5867.562500000000 0.000000000000 0.000000000000 -15214.958000000001 3281.844730000000 49022.722699999998 3783.793700000000 17983.605500000001 15214.958000000001 0.000000000000 5867.562500000000 3783.793700000000 53787.886700000003 -9785.583979999999 -3281.844730000000 -5867.562500000000 0.000000000000 17983.605500000001 -9785.583979999999 9476.375980000001 5 8 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14211.752899999999 -4915.912110000000 0.000000000000 5000.000000000000 0.000000000000 -14211.752899999999 0.000000000000 -5202.684570000000 0.000000000000 0.000000000000 5000.000000000000 4915.912110000000 5202.684570000000 0.000000000000 0.000000000000 -14211.752899999999 4915.912110000000 46832.140599999999 4962.029790000000 14211.602500000001 14211.752899999999 0.000000000000 5202.684570000000 4962.029790000000 47589.500000000000 -14250.511699999999 -4915.912110000000 -5202.684570000000 0.000000000000 14211.602500000001 -14250.511699999999 10786.735400000000 5 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10529.308600000000 -5301.768070000000 0.000000000000 5000.000000000000 0.000000000000 -10529.308600000000 0.000000000000 -6355.546880000000 0.000000000000 0.000000000000 5000.000000000000 5301.768070000000 6355.546880000000 0.000000000000 0.000000000000 -10529.308600000000 5301.768070000000 28491.728500000001 6687.347170000000 13320.400400000000 10529.308600000000 0.000000000000 6355.546880000000 6687.347170000000 30844.371100000000 -11298.663100000000 -5301.768070000000 -6355.546880000000 0.000000000000 13320.400400000000 -11298.663100000000 14033.465800000000 5 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12852.819299999999 -5423.980960000000 0.000000000000 5000.000000000000 0.000000000000 -12852.819299999999 0.000000000000 -5835.052730000000 0.000000000000 0.000000000000 5000.000000000000 5423.980960000000 5835.052730000000 0.000000000000 0.000000000000 -12852.819299999999 5423.980960000000 40490.363299999997 6254.723630000000 14760.308600000000 12852.819299999999 0.000000000000 5835.052730000000 6254.723630000000 41523.796900000001 -14125.644500000000 -5423.980960000000 -5835.052730000000 0.000000000000 14760.308600000000 -14125.644500000000 13084.858399999999 5 36 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12505.538100000000 -5467.494630000000 0.000000000000 5000.000000000000 0.000000000000 -12505.538100000000 0.000000000000 -5429.651370000000 0.000000000000 0.000000000000 5000.000000000000 5467.494630000000 5429.651370000000 0.000000000000 0.000000000000 -12505.538100000000 5467.494630000000 38597.964800000002 5836.537110000000 13230.443400000000 12505.538100000000 0.000000000000 5429.651370000000 5836.537110000000 38757.175799999997 -13845.935500000000 -5467.494630000000 -5429.651370000000 0.000000000000 13230.443400000000 -13845.935500000000 12412.440399999999 5 41 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15505.874000000000 -4558.144530000000 0.000000000000 5000.000000000000 0.000000000000 -15505.874000000000 0.000000000000 4700.819820000000 0.000000000000 0.000000000000 5000.000000000000 4558.144530000000 -4700.819820000000 0.000000000000 0.000000000000 -15505.874000000000 4558.144530000000 52690.628900000003 -4224.186520000000 -14532.093800000001 15505.874000000000 0.000000000000 -4700.819820000000 -4224.186520000000 53038.343800000002 -14083.110400000000 -4558.144530000000 4700.819820000000 0.000000000000 -14532.093800000001 -14083.110400000000 9327.723630000000 5 42 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16086.139600000000 -3402.544680000000 0.000000000000 5000.000000000000 0.000000000000 -16086.139600000000 0.000000000000 3946.297120000000 0.000000000000 0.000000000000 5000.000000000000 3402.544680000000 -3946.297120000000 0.000000000000 0.000000000000 -16086.139600000000 3402.544680000000 56509.902300000002 -2127.976560000000 -12624.856400000001 16086.139600000000 0.000000000000 -3946.297120000000 -2127.976560000000 55904.507799999999 -10684.317400000000 -3402.544680000000 3946.297120000000 0.000000000000 -12624.856400000001 -10684.317400000000 8652.959960000000 5 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14906.177700000000 -5230.920410000000 0.000000000000 5000.000000000000 0.000000000000 -14906.177700000000 0.000000000000 -4983.243650000000 0.000000000000 0.000000000000 5000.000000000000 5230.920410000000 4983.243650000000 0.000000000000 0.000000000000 -14906.177700000000 5230.920410000000 50767.980499999998 5071.791500000000 14520.351600000000 14906.177700000000 0.000000000000 4983.243650000000 5071.791500000000 50456.621099999997 -15818.776400000001 -5230.920410000000 -4983.243650000000 0.000000000000 14520.351600000000 -15818.776400000001 10918.331099999999 6 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11513.563500000000 -2633.613770000000 0.000000000000 5000.000000000000 0.000000000000 -11513.563500000000 0.000000000000 -2776.243650000000 0.000000000000 0.000000000000 5000.000000000000 2633.613770000000 2776.243650000000 0.000000000000 0.000000000000 -11513.563500000000 2633.613770000000 28593.023399999998 1289.366820000000 6168.767580000000 11513.563500000000 0.000000000000 2776.243650000000 1289.366820000000 28876.046900000001 -6060.886230000000 -2633.613770000000 -2776.243650000000 0.000000000000 6168.767580000000 -6060.886230000000 3639.450680000000 6 40 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15726.044900000001 -1614.308590000000 0.000000000000 5000.000000000000 0.000000000000 -15726.044900000001 0.000000000000 5668.318850000000 0.000000000000 0.000000000000 5000.000000000000 1614.308590000000 -5668.318850000000 0.000000000000 0.000000000000 -15726.044900000001 1614.308590000000 50517.117200000001 -1792.182500000000 -17773.275399999999 15726.044900000001 0.000000000000 -5668.318850000000 -1792.182500000000 56273.558599999997 -4950.514160000000 -1614.308590000000 5668.318850000000 0.000000000000 -17773.275399999999 -4950.514160000000 7484.618650000000 6 43 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15551.540000000001 -1368.771850000000 0.000000000000 5000.000000000000 0.000000000000 -15551.540000000001 0.000000000000 5483.334960000000 0.000000000000 0.000000000000 5000.000000000000 1368.771850000000 -5483.334960000000 0.000000000000 0.000000000000 -15551.540000000001 1368.771850000000 50406.429700000001 -1173.617070000000 -17120.578099999999 15551.540000000001 0.000000000000 -5483.334960000000 -1173.617070000000 54919.414100000002 -3961.875730000000 -1368.771850000000 5483.334960000000 0.000000000000 -17120.578099999999 -3961.875730000000 8206.208979999999 6 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14288.025400000000 -1822.476070000000 0.000000000000 5000.000000000000 0.000000000000 -14288.025400000000 0.000000000000 -547.019165000000 0.000000000000 0.000000000000 5000.000000000000 1822.476070000000 547.019165000000 0.000000000000 0.000000000000 -14288.025400000000 1822.476070000000 42729.968800000002 -64.432716400000 259.774109000000 14288.025400000000 0.000000000000 547.019165000000 -64.432716400000 43816.839800000002 -5381.215820000000 -1822.476070000000 -547.019165000000 0.000000000000 259.774109000000 -5381.215820000000 2771.397460000000 6 51 66 3106.000000000000 0.000000000000 0.000000000000 0.000000000000 8172.820310000000 -584.500305000000 0.000000000000 3106.000000000000 0.000000000000 -8172.820310000000 0.000000000000 -1773.505000000000 0.000000000000 0.000000000000 3106.000000000000 584.500305000000 1773.505000000000 0.000000000000 0.000000000000 -8172.820310000000 584.500305000000 21876.277300000002 312.909424000000 4453.312010000000 8172.820310000000 0.000000000000 1773.505000000000 312.909424000000 23009.234400000001 -1536.097410000000 -584.500305000000 -1773.505000000000 0.000000000000 4453.312010000000 -1536.097410000000 1428.227910000000 7 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10092.907200000000 -2031.094480000000 0.000000000000 5000.000000000000 0.000000000000 -10092.907200000000 0.000000000000 -3262.190670000000 0.000000000000 0.000000000000 5000.000000000000 2031.094480000000 3262.190670000000 0.000000000000 0.000000000000 -10092.907200000000 2031.094480000000 21881.732400000001 1131.800900000000 6321.589840000000 10092.907200000000 0.000000000000 3262.190670000000 1131.800900000000 23260.109400000001 -4158.033200000000 -2031.094480000000 -3262.190670000000 0.000000000000 6321.589840000000 -4158.033200000000 3613.123290000000 7 40 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15522.472700000000 -2736.673830000000 0.000000000000 5000.000000000000 0.000000000000 -15522.472700000000 0.000000000000 4963.965330000000 0.000000000000 0.000000000000 5000.000000000000 2736.673830000000 -4963.965330000000 0.000000000000 0.000000000000 -15522.472700000000 2736.673830000000 50440.996099999997 -2627.686770000000 -15397.525400000000 15522.472700000000 0.000000000000 -4963.965330000000 -2627.686770000000 53593.777300000002 -8249.761720000000 -2736.673830000000 4963.965330000000 0.000000000000 -15397.525400000000 -8249.761720000000 7129.115720000000 7 43 66 4960.000000000000 0.000000000000 0.000000000000 0.000000000000 14768.084999999999 -3646.247800000000 0.000000000000 4960.000000000000 0.000000000000 -14768.084999999999 0.000000000000 4853.864750000000 0.000000000000 0.000000000000 4960.000000000000 3646.247800000000 -4853.864750000000 0.000000000000 0.000000000000 -14768.084999999999 3646.247800000000 46970.753900000003 -3523.222170000000 -14489.210900000000 14768.084999999999 0.000000000000 -4853.864750000000 -3523.222170000000 49144.292999999998 -10807.307600000000 -3646.247800000000 4853.864750000000 0.000000000000 -14489.210900000000 -10807.307600000000 7886.849120000000 8 9 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16165.997100000001 -351.101013000000 0.000000000000 5000.000000000000 0.000000000000 -16165.997100000001 0.000000000000 -3513.428960000000 0.000000000000 0.000000000000 5000.000000000000 351.101013000000 3513.428960000000 0.000000000000 0.000000000000 -16165.997100000001 351.101013000000 53789.535199999998 1071.111330000000 11544.860400000000 16165.997100000001 0.000000000000 3513.428960000000 1071.111330000000 59258.644500000002 -1010.616090000000 -351.101013000000 -3513.428960000000 0.000000000000 11544.860400000000 -1010.616090000000 7437.239750000000 8 10 66 4342.000000000000 0.000000000000 0.000000000000 0.000000000000 14331.672900000000 -439.170532000000 0.000000000000 4342.000000000000 0.000000000000 -14331.672900000000 0.000000000000 -5508.484860000000 0.000000000000 0.000000000000 4342.000000000000 439.170532000000 5508.484860000000 0.000000000000 0.000000000000 -14331.672900000000 439.170532000000 47907.359400000001 517.350220000000 18154.896499999999 14331.672900000000 0.000000000000 5508.484860000000 517.350220000000 54645.226600000002 -1423.391360000000 -439.170532000000 -5508.484860000000 0.000000000000 18154.896499999999 -1423.391360000000 7781.314450000000 8 34 66 4048.000000000000 0.000000000000 0.000000000000 0.000000000000 7120.094240000000 -1707.810180000000 0.000000000000 4048.000000000000 0.000000000000 -7120.094240000000 0.000000000000 -24.456516300000 0.000000000000 0.000000000000 4048.000000000000 1707.810180000000 24.456516300000 0.000000000000 0.000000000000 -7120.094240000000 1707.810180000000 13507.659200000000 -94.142089800000 -107.772720000000 7120.094240000000 0.000000000000 24.456516300000 -94.142089800000 13017.034200000000 -3030.582520000000 -1707.810180000000 -24.456516300000 0.000000000000 -107.772720000000 -3030.582520000000 1174.352420000000 8 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10756.705099999999 -2459.892580000000 0.000000000000 5000.000000000000 0.000000000000 -10756.705099999999 0.000000000000 1026.918700000000 0.000000000000 0.000000000000 5000.000000000000 2459.892580000000 -1026.918700000000 0.000000000000 0.000000000000 -10756.705099999999 2459.892580000000 26128.578099999999 -950.548645000000 -2323.458740000000 10756.705099999999 0.000000000000 -1026.918700000000 -950.548645000000 26452.146499999999 -5289.846680000000 -2459.892580000000 1026.918700000000 0.000000000000 -2323.458740000000 -5289.846680000000 3268.545410000000 8 36 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11146.109399999999 -2593.550780000000 0.000000000000 5000.000000000000 0.000000000000 -11146.109399999999 0.000000000000 2548.971440000000 0.000000000000 0.000000000000 5000.000000000000 2593.550780000000 -2548.971440000000 0.000000000000 0.000000000000 -11146.109399999999 2593.550780000000 27678.121100000000 -1578.234990000000 -6861.031250000000 11146.109399999999 0.000000000000 -2548.971440000000 -1578.234990000000 28844.750000000000 -5887.991210000000 -2593.550780000000 2548.971440000000 0.000000000000 -6861.031250000000 -5887.991210000000 4227.253420000000 8 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16563.826200000000 38.505001100000 0.000000000000 5000.000000000000 0.000000000000 -16563.826200000000 0.000000000000 -4281.618650000000 0.000000000000 0.000000000000 5000.000000000000 -38.505001100000 4281.618650000000 0.000000000000 0.000000000000 -16563.826200000000 -38.505001100000 56470.355499999998 1389.185420000000 14002.402300000000 16563.826200000000 0.000000000000 4281.618650000000 1389.185420000000 62190.035199999998 232.034424000000 38.505001100000 -4281.618650000000 0.000000000000 14002.402300000000 232.034424000000 8379.804690000001 8 53 66 4143.000000000000 0.000000000000 0.000000000000 0.000000000000 13823.571300000000 -92.755600000000 0.000000000000 4143.000000000000 0.000000000000 -13823.571300000000 0.000000000000 -4375.559080000000 0.000000000000 0.000000000000 4143.000000000000 92.755600000000 4375.559080000000 0.000000000000 0.000000000000 -13823.571300000000 92.755600000000 46775.410199999998 497.613556000000 14474.152300000000 13823.571300000000 0.000000000000 4375.559080000000 497.613556000000 52299.175799999997 -329.504639000000 -92.755600000000 -4375.559080000000 0.000000000000 14474.152300000000 -329.504639000000 6721.842770000000 8 55 66 2367.000000000000 0.000000000000 0.000000000000 0.000000000000 7712.335940000000 -507.041870000000 0.000000000000 2367.000000000000 0.000000000000 -7712.335940000000 0.000000000000 -3019.964110000000 0.000000000000 0.000000000000 2367.000000000000 507.041870000000 3019.964110000000 0.000000000000 0.000000000000 -7712.335940000000 507.041870000000 25531.175800000001 647.517822000000 9834.276370000000 7712.335940000000 0.000000000000 3019.964110000000 647.517822000000 29066.193400000000 -1641.256100000000 -507.041870000000 -3019.964110000000 0.000000000000 9834.276370000000 -1641.256100000000 4265.714840000000 9 12 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15174.118200000001 -2555.712400000000 0.000000000000 5000.000000000000 0.000000000000 -15174.118200000001 0.000000000000 -5866.443850000000 0.000000000000 0.000000000000 5000.000000000000 2555.712400000000 5866.443850000000 0.000000000000 0.000000000000 -15174.118200000001 2555.712400000000 48219.781300000002 3000.904540000000 17791.431600000000 15174.118200000001 0.000000000000 5866.443850000000 3000.904540000000 53643.851600000002 -7662.356450000000 -2555.712400000000 -5866.443850000000 0.000000000000 17791.431600000000 -7662.356450000000 8720.075199999999 9 36 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14397.924800000001 -5116.019040000000 0.000000000000 5000.000000000000 0.000000000000 -14397.924800000001 0.000000000000 3186.971680000000 0.000000000000 0.000000000000 5000.000000000000 5116.019040000000 -3186.971680000000 0.000000000000 0.000000000000 -14397.924800000001 5116.019040000000 48109.781300000002 -3284.346680000000 -9436.833010000000 14397.924800000001 0.000000000000 -3186.971680000000 -3284.346680000000 44954.312500000000 -14936.272499999999 -5116.019040000000 3186.971680000000 0.000000000000 -9436.833010000000 -14936.272499999999 7836.283200000000 9 37 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14933.569299999999 -5001.882810000000 0.000000000000 5000.000000000000 0.000000000000 -14933.569299999999 0.000000000000 3437.409180000000 0.000000000000 0.000000000000 5000.000000000000 5001.882810000000 -3437.409180000000 0.000000000000 0.000000000000 -14933.569299999999 5001.882810000000 51119.113299999997 -3418.477780000000 -10520.275400000000 14933.569299999999 0.000000000000 -3437.409180000000 -3418.477780000000 48438.062500000000 -15110.506799999999 -5001.882810000000 3437.409180000000 0.000000000000 -10520.275400000000 -15110.506799999999 7940.472660000000 9 38 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15160.097700000000 -2503.297610000000 0.000000000000 5000.000000000000 0.000000000000 -15160.097700000000 0.000000000000 5257.873050000000 0.000000000000 0.000000000000 5000.000000000000 2503.297610000000 -5257.873050000000 0.000000000000 0.000000000000 -15160.097700000000 2503.297610000000 49390.191400000003 -2322.870610000000 -16508.289100000002 15160.097700000000 0.000000000000 -5257.873050000000 -2322.870610000000 53483.222699999998 -7257.354490000000 -2503.297610000000 5257.873050000000 0.000000000000 -16508.289100000002 -7257.354490000000 8092.593260000000 9 39 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15700.040000000001 -4294.185060000000 0.000000000000 5000.000000000000 0.000000000000 -15700.040000000001 0.000000000000 3871.744380000000 0.000000000000 0.000000000000 5000.000000000000 4294.185060000000 -3871.744380000000 0.000000000000 0.000000000000 -15700.040000000001 4294.185060000000 53970.648399999998 -2923.510250000000 -12156.669900000001 15700.040000000001 0.000000000000 -3871.744380000000 -2923.510250000000 53182.156300000002 -13342.322300000000 -4294.185060000000 3871.744380000000 0.000000000000 -12156.669900000001 -13342.322300000000 7856.159670000000 9 50 66 3468.000000000000 0.000000000000 0.000000000000 0.000000000000 8970.639649999999 -2425.305660000000 0.000000000000 3468.000000000000 0.000000000000 -8970.639649999999 0.000000000000 907.221558000000 0.000000000000 0.000000000000 3468.000000000000 2425.305660000000 -907.221558000000 0.000000000000 0.000000000000 -8970.639649999999 2425.305660000000 26632.277300000002 -523.263672000000 -2103.035400000000 8970.639649999999 0.000000000000 -907.221558000000 -523.263672000000 27279.234400000001 -6302.018070000000 -2425.305660000000 907.221558000000 0.000000000000 -2103.035400000000 -6302.018070000000 4581.814450000000 9 54 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15368.433600000000 -1889.776490000000 0.000000000000 5000.000000000000 0.000000000000 -15368.433600000000 0.000000000000 -5436.644530000000 0.000000000000 0.000000000000 5000.000000000000 1889.776490000000 5436.644530000000 0.000000000000 0.000000000000 -15368.433600000000 1889.776490000000 48437.500000000000 2015.806520000000 16561.503900000000 15368.433600000000 0.000000000000 5436.644530000000 2015.806520000000 54443.414100000002 -5778.750980000000 -1889.776490000000 -5436.644530000000 0.000000000000 16561.503900000000 -5778.750980000000 7485.772950000000 9 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13935.735400000000 -3611.334230000000 0.000000000000 5000.000000000000 0.000000000000 -13935.735400000000 0.000000000000 -6088.891110000000 0.000000000000 0.000000000000 5000.000000000000 3611.334230000000 6088.891110000000 0.000000000000 0.000000000000 -13935.735400000000 3611.334230000000 42531.937500000000 4292.547850000000 17013.208999999999 13935.735400000000 0.000000000000 6088.891110000000 4292.547850000000 46880.363299999997 -9847.062500000000 -3611.334230000000 -6088.891110000000 0.000000000000 17013.208999999999 -9847.062500000000 10773.159200000000 10 13 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12359.590800000000 293.662354000000 0.000000000000 5000.000000000000 0.000000000000 -12359.590800000000 0.000000000000 -5564.085450000000 0.000000000000 0.000000000000 5000.000000000000 -293.662354000000 5564.085450000000 0.000000000000 0.000000000000 -12359.590800000000 -293.662354000000 31245.568400000000 -404.990173000000 13982.230500000000 12359.590800000000 0.000000000000 5564.085450000000 -404.990173000000 37646.078099999999 936.266052000000 293.662354000000 -5564.085450000000 0.000000000000 13982.230500000000 936.266052000000 6585.686520000000 10 37 66 4435.000000000000 0.000000000000 0.000000000000 0.000000000000 12814.384800000000 -309.558014000000 0.000000000000 4435.000000000000 0.000000000000 -12814.384800000000 0.000000000000 5225.416990000000 0.000000000000 0.000000000000 4435.000000000000 309.558014000000 -5225.416990000000 0.000000000000 0.000000000000 -12814.384800000000 309.558014000000 38572.718800000002 -213.251572000000 -15176.680700000001 12814.384800000000 0.000000000000 -5225.416990000000 -213.251572000000 43652.218800000002 -492.188812000000 -309.558014000000 5225.416990000000 0.000000000000 -15176.680700000001 -492.188812000000 7540.635250000000 10 39 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14360.737300000001 -494.315369000000 0.000000000000 5000.000000000000 0.000000000000 -14360.737300000001 0.000000000000 5197.089840000000 0.000000000000 0.000000000000 5000.000000000000 494.315369000000 -5197.089840000000 0.000000000000 0.000000000000 -14360.737300000001 494.315369000000 42826.734400000001 -169.757965000000 -14930.059600000001 14360.737300000001 0.000000000000 -5197.089840000000 -169.757965000000 47242.507799999999 -1046.717290000000 -494.315369000000 5197.089840000000 0.000000000000 -14930.059600000001 -1046.717290000000 6981.366210000000 10 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12473.323200000001 -417.070953000000 0.000000000000 5000.000000000000 0.000000000000 -12473.323200000001 0.000000000000 -4998.915530000000 0.000000000000 0.000000000000 5000.000000000000 417.070953000000 4998.915530000000 0.000000000000 0.000000000000 -12473.323200000001 417.070953000000 32374.894499999999 146.696060000000 12652.967800000000 12473.323200000001 0.000000000000 4998.915530000000 146.696060000000 37237.820299999999 -728.079529000000 -417.070953000000 -4998.915530000000 0.000000000000 12652.967800000000 -728.079529000000 5967.950680000000 11 13 66 2520.000000000000 0.000000000000 0.000000000000 0.000000000000 5748.491700000000 -579.493652000000 0.000000000000 2520.000000000000 0.000000000000 -5748.491700000000 0.000000000000 -2700.447020000000 0.000000000000 0.000000000000 2520.000000000000 579.493652000000 2700.447020000000 0.000000000000 0.000000000000 -5748.491700000000 579.493652000000 13674.543900000001 567.412842000000 6430.777340000000 5748.491700000000 0.000000000000 2700.447020000000 567.412842000000 16708.304700000001 -1233.853640000000 -579.493652000000 -2700.447020000000 0.000000000000 6430.777340000000 -1233.853640000000 3341.685060000000 11 51 66 4555.000000000000 0.000000000000 0.000000000000 0.000000000000 9389.986330000000 -2349.358400000000 0.000000000000 4555.000000000000 0.000000000000 -9389.986330000000 0.000000000000 -778.341980000000 0.000000000000 0.000000000000 4555.000000000000 2349.358400000000 778.341980000000 0.000000000000 0.000000000000 -9389.986330000000 2349.358400000000 21119.777300000002 209.921906000000 1390.704350000000 9389.986330000000 0.000000000000 778.341980000000 209.921906000000 20635.683600000000 -4995.561040000000 -2349.358400000000 -778.341980000000 0.000000000000 1390.704350000000 -4995.561040000000 2416.726560000000 11 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11385.865200000000 -1551.756590000000 0.000000000000 5000.000000000000 0.000000000000 -11385.865200000000 0.000000000000 -4513.622560000000 0.000000000000 0.000000000000 5000.000000000000 1551.756590000000 4513.622560000000 0.000000000000 0.000000000000 -11385.865200000000 1551.756590000000 27509.808600000000 1108.309570000000 10698.716800000000 11385.865200000000 0.000000000000 4513.622560000000 1108.309570000000 31623.330099999999 -3387.459230000000 -1551.756590000000 -4513.622560000000 0.000000000000 10698.716800000000 -3387.459230000000 5490.933590000000 12 14 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9946.333010000000 -4579.999020000000 0.000000000000 5000.000000000000 0.000000000000 -9946.333010000000 0.000000000000 -5087.762700000000 0.000000000000 0.000000000000 5000.000000000000 4579.999020000000 5087.762700000000 0.000000000000 0.000000000000 -9946.333010000000 4579.999020000000 25567.455099999999 4814.710940000000 10531.428700000000 9946.333010000000 0.000000000000 5087.762700000000 4814.710940000000 26776.804700000001 -8843.135740000000 -4579.999020000000 -5087.762700000000 0.000000000000 10531.428700000000 -8843.135740000000 10250.059600000001 12 15 66 4899.000000000000 0.000000000000 0.000000000000 0.000000000000 7851.604980000000 -4832.904790000000 0.000000000000 4899.000000000000 0.000000000000 -7851.604980000000 0.000000000000 -4430.037110000000 0.000000000000 0.000000000000 4899.000000000000 4832.904790000000 4430.037110000000 0.000000000000 0.000000000000 -7851.604980000000 4832.904790000000 18065.373000000000 4665.845700000000 7193.337890000000 7851.604980000000 0.000000000000 4430.037110000000 4665.845700000000 17322.113300000001 -7637.964840000000 -4832.904790000000 -4430.037110000000 0.000000000000 7193.337890000000 -7637.964840000000 9658.176760000000 12 51 66 4569.000000000000 0.000000000000 0.000000000000 0.000000000000 8374.916020000001 -4632.936040000000 0.000000000000 4569.000000000000 0.000000000000 -8374.916020000001 0.000000000000 -51.834816000000 0.000000000000 0.000000000000 4569.000000000000 4632.936040000000 51.834816000000 0.000000000000 0.000000000000 -8374.916020000001 4632.936040000000 20646.435500000000 78.603874200000 2.258328440000 8374.916020000001 0.000000000000 51.834816000000 78.603874200000 15786.013700000000 -8509.169920000000 -4632.936040000000 -51.834816000000 0.000000000000 2.258328440000 -8509.169920000000 5215.713870000000 12 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10283.187500000000 -4820.690430000000 0.000000000000 5000.000000000000 0.000000000000 -10283.187500000000 0.000000000000 424.828064000000 0.000000000000 0.000000000000 5000.000000000000 4820.690430000000 -424.828064000000 0.000000000000 0.000000000000 -10283.187500000000 4820.690430000000 26650.093799999999 -375.498322000000 -1064.368040000000 10283.187500000000 0.000000000000 -424.828064000000 -375.498322000000 22089.652300000002 -9868.376950000000 -4820.690430000000 424.828064000000 0.000000000000 -1064.368040000000 -9868.376950000000 5413.948240000000 12 57 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9023.965819999999 -5325.959470000000 0.000000000000 5000.000000000000 0.000000000000 -9023.965819999999 0.000000000000 -5311.699710000000 0.000000000000 0.000000000000 5000.000000000000 5325.959470000000 5311.699710000000 0.000000000000 0.000000000000 -9023.965819999999 5325.959470000000 23207.410199999998 5792.706540000000 9857.098630000000 9023.965819999999 0.000000000000 5311.699710000000 5792.706540000000 22994.982400000001 -9384.309569999999 -5325.959470000000 -5311.699710000000 0.000000000000 9857.098630000000 -9384.309569999999 12135.774400000000 13 53 66 4058.000000000000 0.000000000000 0.000000000000 0.000000000000 7805.162110000000 -1514.293700000000 0.000000000000 4058.000000000000 0.000000000000 -7805.162110000000 0.000000000000 2218.393800000000 0.000000000000 0.000000000000 4058.000000000000 1514.293700000000 -2218.393800000000 0.000000000000 0.000000000000 -7805.162110000000 1514.293700000000 15834.039100000000 -807.510681000000 -4348.840820000000 7805.162110000000 0.000000000000 -2218.393800000000 -807.510681000000 16627.831999999999 -2858.540530000000 -1514.293700000000 2218.393800000000 0.000000000000 -4348.840820000000 -2858.540530000000 1949.822630000000 13 58 66 2427.000000000000 0.000000000000 0.000000000000 0.000000000000 7091.268550000000 -2178.996090000000 0.000000000000 2427.000000000000 0.000000000000 -7091.268550000000 0.000000000000 -3002.514890000000 0.000000000000 0.000000000000 2427.000000000000 2178.996090000000 3002.514890000000 0.000000000000 0.000000000000 -7091.268550000000 2178.996090000000 22851.298800000000 2677.930420000000 8863.560550000000 7091.268550000000 0.000000000000 3002.514890000000 2677.930420000000 24701.263700000000 -6332.479980000000 -2178.996090000000 -3002.514890000000 0.000000000000 8863.560550000000 -6332.479980000000 5776.589840000000 14 18 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11321.564500000000 -6329.463870000000 0.000000000000 5000.000000000000 0.000000000000 -11321.564500000000 0.000000000000 -5286.352540000000 0.000000000000 0.000000000000 5000.000000000000 6329.463870000000 5286.352540000000 0.000000000000 0.000000000000 -11321.564500000000 6329.463870000000 34554.285199999998 6662.956050000000 12054.978499999999 11321.564500000000 0.000000000000 5286.352540000000 6662.956050000000 32368.111300000000 -14403.833000000001 -6329.463870000000 -5286.352540000000 0.000000000000 12054.978499999999 -14403.833000000001 13977.715800000000 14 55 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10096.680700000001 -3795.837890000000 0.000000000000 5000.000000000000 0.000000000000 -10096.680700000001 0.000000000000 1129.555660000000 0.000000000000 0.000000000000 5000.000000000000 3795.837890000000 -1129.555660000000 0.000000000000 0.000000000000 -10096.680700000001 3795.837890000000 24576.888700000000 -451.125305000000 -2482.953860000000 10096.680700000001 0.000000000000 -1129.555660000000 -451.125305000000 22183.769499999999 -7586.267090000000 -3795.837890000000 1129.555660000000 0.000000000000 -2482.953860000000 -7586.267090000000 4156.661620000000 14 61 66 2941.000000000000 0.000000000000 0.000000000000 0.000000000000 6130.766110000000 -3842.756590000000 0.000000000000 2941.000000000000 0.000000000000 -6130.766110000000 0.000000000000 -4039.450680000000 0.000000000000 0.000000000000 2941.000000000000 3842.756590000000 4039.450680000000 0.000000000000 0.000000000000 -6130.766110000000 3842.756590000000 18126.599600000001 5276.644530000000 8436.383790000000 6130.766110000000 0.000000000000 4039.450680000000 5276.644530000000 18674.902300000002 -7984.466800000000 -3842.756590000000 -4039.450680000000 0.000000000000 8436.383790000000 -7984.466800000000 10594.870100000000 14 62 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10146.562500000000 -6405.673340000000 0.000000000000 5000.000000000000 0.000000000000 -10146.562500000000 0.000000000000 -6026.141600000000 0.000000000000 0.000000000000 5000.000000000000 6405.673340000000 6026.141600000000 0.000000000000 0.000000000000 -10146.562500000000 6405.673340000000 29669.464800000002 7699.591310000000 12342.252899999999 10146.562500000000 0.000000000000 6026.141600000000 7699.591310000000 28835.296900000001 -13043.635700000001 -6405.673340000000 -6026.141600000000 0.000000000000 12342.252899999999 -13043.635700000001 15684.064500000000 14 63 66 3723.000000000000 0.000000000000 0.000000000000 0.000000000000 7382.515630000000 -4737.524410000000 0.000000000000 3723.000000000000 0.000000000000 -7382.515630000000 0.000000000000 -4350.114260000000 0.000000000000 0.000000000000 3723.000000000000 4737.524410000000 4350.114260000000 0.000000000000 0.000000000000 -7382.515630000000 4737.524410000000 21198.728500000001 5510.062990000000 8729.384770000001 7382.515630000000 0.000000000000 4350.114260000000 5510.062990000000 20347.585899999998 -9460.955080000000 -4737.524410000000 -4350.114260000000 0.000000000000 8729.384770000001 -9460.955080000000 11317.643599999999 15 16 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14353.637699999999 2417.461430000000 0.000000000000 5000.000000000000 0.000000000000 -14353.637699999999 0.000000000000 -2219.628420000000 0.000000000000 0.000000000000 5000.000000000000 -2417.461430000000 2219.628420000000 0.000000000000 0.000000000000 -14353.637699999999 -2417.461430000000 46225.933599999997 1452.209230000000 4981.228030000000 14353.637699999999 0.000000000000 2219.628420000000 1452.209230000000 48059.160199999998 7595.297360000000 2417.461430000000 -2219.628420000000 0.000000000000 4981.228030000000 7595.297360000000 8656.449220000000 15 17 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11080.082000000000 27.449625000000 0.000000000000 5000.000000000000 0.000000000000 -11080.082000000000 0.000000000000 -3763.891600000000 0.000000000000 0.000000000000 5000.000000000000 -27.449625000000 3763.891600000000 0.000000000000 0.000000000000 -11080.082000000000 -27.449625000000 27526.466799999998 997.682129000000 8111.642580000000 11080.082000000000 0.000000000000 3763.891600000000 997.682129000000 31647.541000000001 1153.608400000000 27.449625000000 -3763.891600000000 0.000000000000 8111.642580000000 1153.608400000000 7080.415530000000 15 19 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11227.319299999999 -2506.564210000000 0.000000000000 5000.000000000000 0.000000000000 -11227.319299999999 0.000000000000 -5106.958500000000 0.000000000000 0.000000000000 5000.000000000000 2506.564210000000 5106.958500000000 0.000000000000 0.000000000000 -11227.319299999999 2506.564210000000 27365.410199999998 2479.143070000000 11417.915000000001 11227.319299999999 0.000000000000 5106.958500000000 2479.143070000000 31139.398399999998 -5769.941890000000 -2506.564210000000 -5106.958500000000 0.000000000000 11417.915000000001 -5769.941890000000 6995.138670000000 15 55 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8814.306640000001 -1578.305180000000 0.000000000000 5000.000000000000 0.000000000000 -8814.306640000001 0.000000000000 2466.169680000000 0.000000000000 0.000000000000 5000.000000000000 1578.305180000000 -2466.169680000000 0.000000000000 0.000000000000 -8814.306640000001 1578.305180000000 17010.421900000001 -494.688934000000 -4347.856930000000 8814.306640000001 0.000000000000 -2466.169680000000 -494.688934000000 17755.943400000000 -2842.360110000000 -1578.305180000000 2466.169680000000 0.000000000000 -4347.856930000000 -2842.360110000000 2447.581050000000 15 60 66 2222.000000000000 0.000000000000 0.000000000000 0.000000000000 7239.000980000000 -735.878601000000 0.000000000000 2222.000000000000 0.000000000000 -7239.000980000000 0.000000000000 -2634.207280000000 0.000000000000 0.000000000000 2222.000000000000 735.878601000000 2634.207280000000 0.000000000000 0.000000000000 -7239.000980000000 735.878601000000 24009.984400000001 852.673828000000 8604.736330000000 7239.000980000000 0.000000000000 2634.207280000000 852.673828000000 26854.839800000002 -2353.114260000000 -735.878601000000 -2634.207280000000 0.000000000000 8604.736330000000 -2353.114260000000 3495.431640000000 15 61 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14436.554700000001 -1773.331420000000 0.000000000000 5000.000000000000 0.000000000000 -14436.554700000001 0.000000000000 -5709.136720000000 0.000000000000 0.000000000000 5000.000000000000 1773.331420000000 5709.136720000000 0.000000000000 0.000000000000 -14436.554700000001 1773.331420000000 43217.273399999998 1873.492920000000 16569.456999999999 14436.554700000001 0.000000000000 5709.136720000000 1873.492920000000 48973.031300000002 -5027.047850000000 -1773.331420000000 -5709.136720000000 0.000000000000 16569.456999999999 -5027.047850000000 7726.049800000000 15 63 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12526.815399999999 -2721.136230000000 0.000000000000 5000.000000000000 0.000000000000 -12526.815399999999 0.000000000000 -4467.009280000000 0.000000000000 0.000000000000 5000.000000000000 2721.136230000000 4467.009280000000 0.000000000000 0.000000000000 -12526.815399999999 2721.136230000000 33946.335899999998 2289.932860000000 11369.889600000000 12526.815399999999 0.000000000000 4467.009280000000 2289.932860000000 36499.925799999997 -6654.483400000000 -2721.136230000000 -4467.009280000000 0.000000000000 11369.889600000000 -6654.483400000000 6060.637700000000 15 64 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12330.515600000001 -2147.744630000000 0.000000000000 5000.000000000000 0.000000000000 -12330.515600000001 0.000000000000 -5645.982910000000 0.000000000000 0.000000000000 5000.000000000000 2147.744630000000 5645.982910000000 0.000000000000 0.000000000000 -12330.515600000001 2147.744630000000 32524.863300000001 2375.729250000000 14094.430700000001 12330.515600000001 0.000000000000 5645.982910000000 2375.729250000000 37758.949200000003 -5188.252440000000 -2147.744630000000 -5645.982910000000 0.000000000000 14094.430700000001 -5188.252440000000 7763.838870000000 16 18 66 1828.000000000000 0.000000000000 0.000000000000 0.000000000000 4956.604980000000 -1366.236690000000 0.000000000000 1828.000000000000 0.000000000000 -4956.604980000000 0.000000000000 -1379.949340000000 0.000000000000 0.000000000000 1828.000000000000 1366.236690000000 1379.949340000000 0.000000000000 0.000000000000 -4956.604980000000 1366.236690000000 15186.751000000000 845.748108000000 3547.144780000000 4956.604980000000 0.000000000000 1379.949340000000 845.748108000000 15273.043000000000 -3920.523930000000 -1366.236690000000 -1379.949340000000 0.000000000000 3547.144780000000 -3920.523930000000 2675.567870000000 16 19 66 1899.000000000000 0.000000000000 0.000000000000 0.000000000000 4726.600100000000 -1102.741700000000 0.000000000000 1899.000000000000 0.000000000000 -4726.600100000000 0.000000000000 -2077.796140000000 0.000000000000 0.000000000000 1899.000000000000 1102.741700000000 2077.796140000000 0.000000000000 0.000000000000 -4726.600100000000 1102.741700000000 12992.009800000000 1146.159670000000 5338.987790000000 4726.600100000000 0.000000000000 2077.796140000000 1146.159670000000 14559.941400000000 -2596.345460000000 -1102.741700000000 -2077.796140000000 0.000000000000 5338.987790000000 -2596.345460000000 3165.913090000000 16 57 66 2919.000000000000 0.000000000000 0.000000000000 0.000000000000 9229.767580000000 -3360.719730000000 0.000000000000 2919.000000000000 0.000000000000 -9229.767580000000 0.000000000000 -646.070984000000 0.000000000000 0.000000000000 2919.000000000000 3360.719730000000 646.070984000000 0.000000000000 0.000000000000 -9229.767580000000 3360.719730000000 33729.035199999998 595.195740000000 1718.108640000000 9229.767580000000 0.000000000000 646.070984000000 595.195740000000 30536.691400000000 -10868.433600000000 -3360.719730000000 -646.070984000000 0.000000000000 1718.108640000000 -10868.433600000000 4884.221190000000 16 58 66 3648.000000000000 0.000000000000 0.000000000000 0.000000000000 11628.793000000000 -3723.295410000000 0.000000000000 3648.000000000000 0.000000000000 -11628.793000000000 0.000000000000 -761.868958000000 0.000000000000 0.000000000000 3648.000000000000 3723.295410000000 761.868958000000 0.000000000000 0.000000000000 -11628.793000000000 3723.295410000000 41521.160199999998 996.564514000000 1894.401000000000 11628.793000000000 0.000000000000 761.868958000000 996.564514000000 40205.539100000002 -11976.155300000000 -3723.295410000000 -761.868958000000 0.000000000000 1894.401000000000 -11976.155300000000 6969.784180000000 16 61 66 4903.000000000000 0.000000000000 0.000000000000 0.000000000000 16033.361300000000 -3621.188720000000 0.000000000000 4903.000000000000 0.000000000000 -16033.361300000000 0.000000000000 -5415.064450000000 0.000000000000 0.000000000000 4903.000000000000 3621.188720000000 5415.064450000000 0.000000000000 0.000000000000 -16033.361300000000 3621.188720000000 55963.367200000001 3575.797360000000 17748.781200000001 16033.361300000000 0.000000000000 5415.064450000000 3575.797360000000 59128.355499999998 -11828.636699999999 -3621.188720000000 -5415.064450000000 0.000000000000 17748.781200000001 -11828.636699999999 9896.115229999999 16 62 66 3801.000000000000 0.000000000000 0.000000000000 0.000000000000 12430.165999999999 -2773.187990000000 0.000000000000 3801.000000000000 0.000000000000 -12430.165999999999 0.000000000000 -4051.243900000000 0.000000000000 0.000000000000 3801.000000000000 2773.187990000000 4051.243900000000 0.000000000000 0.000000000000 -12430.165999999999 2773.187990000000 43685.574200000003 2566.393550000000 13322.920899999999 12430.165999999999 0.000000000000 4051.243900000000 2566.393550000000 45700.812500000000 -9153.852540000000 -2773.187990000000 -4051.243900000000 0.000000000000 13322.920899999999 -9153.852540000000 7574.660640000000 16 63 66 1025.000000000000 0.000000000000 0.000000000000 0.000000000000 3196.131100000000 -660.334839000000 0.000000000000 1025.000000000000 0.000000000000 -3196.131100000000 0.000000000000 -1019.358400000000 0.000000000000 0.000000000000 1025.000000000000 660.334839000000 1019.358400000000 0.000000000000 0.000000000000 -3196.131100000000 660.334839000000 10767.942400000000 570.250977000000 3236.319580000000 3196.131100000000 0.000000000000 1019.358400000000 570.250977000000 11323.510700000001 -2087.836180000000 -660.334839000000 -1019.358400000000 0.000000000000 3236.319580000000 -2087.836180000000 1780.907350000000 16 64 66 1532.000000000000 0.000000000000 0.000000000000 0.000000000000 4312.114260000000 -1056.572880000000 0.000000000000 1532.000000000000 0.000000000000 -4312.114260000000 0.000000000000 -1881.781740000000 0.000000000000 0.000000000000 1532.000000000000 1056.572880000000 1881.781740000000 0.000000000000 0.000000000000 -4312.114260000000 1056.572880000000 13069.149400000000 1306.907350000000 5346.743650000000 4312.114260000000 0.000000000000 1881.781740000000 1306.907350000000 14691.172900000000 -3017.286870000000 -1056.572880000000 -1881.781740000000 0.000000000000 5346.743650000000 -3017.286870000000 3190.960940000000 17 20 66 2186.000000000000 0.000000000000 0.000000000000 0.000000000000 5398.289550000000 -2487.963620000000 0.000000000000 2186.000000000000 0.000000000000 -5398.289550000000 0.000000000000 -2496.267090000000 0.000000000000 0.000000000000 2186.000000000000 2487.963620000000 2496.267090000000 0.000000000000 0.000000000000 -5398.289550000000 2487.963620000000 16727.121100000000 2794.274900000000 6406.592770000000 5398.289550000000 0.000000000000 2496.267090000000 2794.274900000000 16863.689500000000 -6052.739260000000 -2487.963620000000 -2496.267090000000 0.000000000000 6406.592770000000 -6052.739260000000 5849.092290000000 17 57 66 2103.000000000000 0.000000000000 0.000000000000 0.000000000000 5262.000490000000 -2385.714110000000 0.000000000000 2103.000000000000 0.000000000000 -5262.000490000000 0.000000000000 -831.706665000000 0.000000000000 0.000000000000 2103.000000000000 2385.714110000000 831.706665000000 0.000000000000 0.000000000000 -5262.000490000000 2385.714110000000 16737.105500000001 1108.578000000000 2637.151860000000 5262.000490000000 0.000000000000 831.706665000000 1108.578000000000 14763.342800000000 -6174.639650000000 -2385.714110000000 -831.706665000000 0.000000000000 2637.151860000000 -6174.639650000000 3647.038090000000 17 58 66 2663.000000000000 0.000000000000 0.000000000000 0.000000000000 7898.396480000000 -3273.329590000000 0.000000000000 2663.000000000000 0.000000000000 -7898.396480000000 0.000000000000 -1849.660160000000 0.000000000000 0.000000000000 2663.000000000000 3273.329590000000 1849.660160000000 0.000000000000 0.000000000000 -7898.396480000000 3273.329590000000 27608.896499999999 2305.664310000000 5512.003910000000 7898.396480000000 0.000000000000 1849.660160000000 2305.664310000000 24862.400399999999 -9732.689450000000 -3273.329590000000 -1849.660160000000 0.000000000000 5512.003910000000 -9732.689450000000 5471.736820000000 17 61 66 2730.000000000000 0.000000000000 0.000000000000 0.000000000000 8900.637699999999 -3307.789790000000 0.000000000000 2730.000000000000 0.000000000000 -8900.637699999999 0.000000000000 -2349.801760000000 0.000000000000 0.000000000000 2730.000000000000 3307.789790000000 2349.801760000000 0.000000000000 0.000000000000 -8900.637699999999 3307.789790000000 33255.285199999998 2840.070800000000 7712.998540000000 8900.637699999999 0.000000000000 2349.801760000000 2840.070800000000 31176.955099999999 -10789.818400000000 -3307.789790000000 -2349.801760000000 0.000000000000 7712.998540000000 -10789.818400000000 6190.874020000000 17 62 66 2146.000000000000 0.000000000000 0.000000000000 0.000000000000 6028.451170000000 -2562.265140000000 0.000000000000 2146.000000000000 0.000000000000 -6028.451170000000 0.000000000000 -1738.532960000000 0.000000000000 0.000000000000 2146.000000000000 2562.265140000000 1738.532960000000 0.000000000000 0.000000000000 -6028.451170000000 2562.265140000000 20748.869100000000 2050.512210000000 4994.993160000000 6028.451170000000 0.000000000000 1738.532960000000 2050.512210000000 19058.550800000001 -7179.415530000000 -2562.265140000000 -1738.532960000000 0.000000000000 4994.993160000000 -7179.415530000000 4747.156250000000 17 63 66 1744.000000000000 0.000000000000 0.000000000000 0.000000000000 4104.161620000000 -1978.185910000000 0.000000000000 1744.000000000000 0.000000000000 -4104.161620000000 0.000000000000 -1512.061160000000 0.000000000000 0.000000000000 1744.000000000000 1978.185910000000 1512.061160000000 0.000000000000 0.000000000000 -4104.161620000000 1978.185910000000 12187.889600000000 1670.773320000000 3582.838620000000 4104.161620000000 0.000000000000 1512.061160000000 1670.773320000000 11359.943400000000 -4630.784180000000 -1978.185910000000 -1512.061160000000 0.000000000000 3582.838620000000 -4630.784180000000 3832.319340000000 17 65 66 3064.000000000000 0.000000000000 0.000000000000 0.000000000000 8184.217290000000 -3303.552000000000 0.000000000000 3064.000000000000 0.000000000000 -8184.217290000000 0.000000000000 -3837.772460000000 0.000000000000 0.000000000000 3064.000000000000 3303.552000000000 3837.772460000000 0.000000000000 0.000000000000 -8184.217290000000 3303.552000000000 26067.351600000002 4133.564450000000 10390.024400000000 8184.217290000000 0.000000000000 3837.772460000000 4133.564450000000 27422.654299999998 -8802.962890000001 -3303.552000000000 -3837.772460000000 0.000000000000 10390.024400000000 -8802.962890000001 8604.239260000000 18 21 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13432.813500000000 -2707.697750000000 0.000000000000 5000.000000000000 0.000000000000 -13432.813500000000 0.000000000000 -4618.682130000000 0.000000000000 0.000000000000 5000.000000000000 2707.697750000000 4618.682130000000 0.000000000000 0.000000000000 -13432.813500000000 2707.697750000000 38408.742200000001 2293.242430000000 12519.410200000000 13432.813500000000 0.000000000000 4618.682130000000 2293.242430000000 41206.292999999998 -7125.341800000000 -2707.697750000000 -4618.682130000000 0.000000000000 12519.410200000000 -7125.341800000000 6587.940430000000 18 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13955.850600000000 -1824.539790000000 0.000000000000 5000.000000000000 0.000000000000 -13955.850600000000 0.000000000000 -6097.750000000000 0.000000000000 0.000000000000 5000.000000000000 1824.539790000000 6097.750000000000 0.000000000000 0.000000000000 -13955.850600000000 1824.539790000000 40396.738299999997 2393.575680000000 17109.566400000000 13955.850600000000 0.000000000000 6097.750000000000 2393.575680000000 46925.011700000003 -5095.954590000000 -1824.539790000000 -6097.750000000000 0.000000000000 17109.566400000000 -5095.954590000000 8918.256840000000 18 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12790.699199999999 -3413.278560000000 0.000000000000 5000.000000000000 0.000000000000 -12790.699199999999 0.000000000000 3756.363040000000 0.000000000000 0.000000000000 5000.000000000000 3413.278560000000 -3756.363040000000 0.000000000000 0.000000000000 -12790.699199999999 3413.278560000000 35317.988299999997 -2561.042240000000 -9596.084960000000 12790.699199999999 0.000000000000 -3756.363040000000 -2561.042240000000 36094.347699999998 -8667.966800000000 -3413.278560000000 3756.363040000000 0.000000000000 -9596.084960000000 -8667.966800000000 5482.338380000000 18 57 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14291.239299999999 -2754.901610000000 0.000000000000 5000.000000000000 0.000000000000 -14291.239299999999 0.000000000000 4220.849610000000 0.000000000000 0.000000000000 5000.000000000000 2754.901610000000 -4220.849610000000 0.000000000000 0.000000000000 -14291.239299999999 2754.901610000000 43227.070299999999 -2402.637940000000 -12234.046899999999 14291.239299999999 0.000000000000 -4220.849610000000 -2402.637940000000 45587.796900000001 -7698.346680000000 -2754.901610000000 4220.849610000000 0.000000000000 -12234.046899999999 -7698.346680000000 5784.519040000000 18 58 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15096.946300000000 -2397.524410000000 0.000000000000 5000.000000000000 0.000000000000 -15096.946300000000 0.000000000000 4521.178710000000 0.000000000000 0.000000000000 5000.000000000000 2397.524410000000 -4521.178710000000 0.000000000000 0.000000000000 -15096.946300000000 2397.524410000000 47281.578099999999 -2331.860840000000 -13679.122100000001 15096.946300000000 0.000000000000 -4521.178710000000 -2331.860840000000 50608.152300000002 -7189.760740000000 -2397.524410000000 4521.178710000000 0.000000000000 -13679.122100000001 -7189.760740000000 6008.742680000000 18 61 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15664.030300000000 -2451.865230000000 0.000000000000 5000.000000000000 0.000000000000 -15664.030300000000 0.000000000000 3708.782960000000 0.000000000000 0.000000000000 5000.000000000000 2451.865230000000 -3708.782960000000 0.000000000000 0.000000000000 -15664.030300000000 2451.865230000000 50641.234400000001 -1765.033690000000 -11820.840800000000 15664.030300000000 0.000000000000 -3708.782960000000 -1765.033690000000 52841.003900000003 -7607.951660000000 -2451.865230000000 3708.782960000000 0.000000000000 -11820.840800000000 -7607.951660000000 4738.778810000000 18 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14717.755900000000 -1053.825810000000 0.000000000000 5000.000000000000 0.000000000000 -14717.755900000000 0.000000000000 -5145.124510000000 0.000000000000 0.000000000000 5000.000000000000 1053.825810000000 5145.124510000000 0.000000000000 0.000000000000 -14717.755900000000 1053.825810000000 45218.347699999998 1342.668090000000 14992.887699999999 14717.755900000000 0.000000000000 5145.124510000000 1342.668090000000 49794.125000000000 -2656.787600000000 -1053.825810000000 -5145.124510000000 0.000000000000 14992.887699999999 -2656.787600000000 7344.732910000000 19 22 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12953.097700000000 -1125.766480000000 0.000000000000 5000.000000000000 0.000000000000 -12953.097700000000 0.000000000000 -4700.888670000000 0.000000000000 0.000000000000 5000.000000000000 1125.766480000000 4700.888670000000 0.000000000000 0.000000000000 -12953.097700000000 1125.766480000000 36636.167999999998 1048.686520000000 12121.168000000000 12953.097700000000 0.000000000000 4700.888670000000 1048.686520000000 40874.472699999998 -2339.575200000000 -1125.766480000000 -4700.888670000000 0.000000000000 12121.168000000000 -2339.575200000000 5975.618160000000 19 23 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15680.391600000001 -1011.107360000000 0.000000000000 5000.000000000000 0.000000000000 -15680.391600000001 0.000000000000 -5331.106450000000 0.000000000000 0.000000000000 5000.000000000000 1011.107360000000 5331.106450000000 0.000000000000 0.000000000000 -15680.391600000001 1011.107360000000 50314.925799999997 1002.116090000000 16697.283200000002 15680.391600000001 0.000000000000 5331.106450000000 1002.116090000000 55571.777300000002 -3354.295650000000 -1011.107360000000 -5331.106450000000 0.000000000000 16697.283200000002 -3354.295650000000 6914.129390000000 19 24 66 1726.000000000000 0.000000000000 0.000000000000 0.000000000000 5463.401860000000 -346.946594000000 0.000000000000 1726.000000000000 0.000000000000 -5463.401860000000 0.000000000000 -2210.379880000000 0.000000000000 0.000000000000 1726.000000000000 346.946594000000 2210.379880000000 0.000000000000 0.000000000000 -5463.401860000000 346.946594000000 17607.271499999999 472.532684000000 7007.272950000000 5463.401860000000 0.000000000000 2210.379880000000 472.532684000000 20212.833999999999 -1141.718990000000 -346.946594000000 -2210.379880000000 0.000000000000 7007.272950000000 -1141.718990000000 3133.620120000000 19 33 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14740.192400000000 -1673.722780000000 0.000000000000 5000.000000000000 0.000000000000 -14740.192400000000 0.000000000000 -4936.031740000000 0.000000000000 0.000000000000 5000.000000000000 1673.722780000000 4936.031740000000 0.000000000000 0.000000000000 -14740.192400000000 1673.722780000000 46232.113299999997 1475.724980000000 14466.063500000000 14740.192400000000 0.000000000000 4936.031740000000 1475.724980000000 50246.378900000003 -4686.367680000000 -1673.722780000000 -4936.031740000000 0.000000000000 14466.063500000000 -4686.367680000000 6409.406250000000 19 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13556.062500000000 -2397.686520000000 0.000000000000 5000.000000000000 0.000000000000 -13556.062500000000 0.000000000000 -3420.788570000000 0.000000000000 0.000000000000 5000.000000000000 2397.686520000000 3420.788570000000 0.000000000000 0.000000000000 -13556.062500000000 2397.686520000000 40234.296900000001 1337.038090000000 9141.166020000001 13556.062500000000 0.000000000000 3420.788570000000 1337.038090000000 41539.136700000003 -6161.026370000000 -2397.686520000000 -3420.788570000000 0.000000000000 9141.166020000001 -6161.026370000000 4757.682130000000 19 62 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14071.235400000000 -3202.104490000000 0.000000000000 5000.000000000000 0.000000000000 -14071.235400000000 0.000000000000 2811.734620000000 0.000000000000 0.000000000000 5000.000000000000 3202.104490000000 -2811.734620000000 0.000000000000 0.000000000000 -14071.235400000000 3202.104490000000 42376.179700000001 -1947.434080000000 -7573.731450000000 14071.235400000000 0.000000000000 -2811.734620000000 -1947.434080000000 42317.187500000000 -8848.179690000001 -3202.104490000000 2811.734620000000 0.000000000000 -7573.731450000000 -8848.179690000001 4468.120610000000 20 24 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15488.953100000001 -1447.543460000000 0.000000000000 5000.000000000000 0.000000000000 -15488.953100000001 0.000000000000 -5704.087400000000 0.000000000000 0.000000000000 5000.000000000000 1447.543460000000 5704.087400000000 0.000000000000 0.000000000000 -15488.953100000001 1447.543460000000 49786.792999999998 1757.230100000000 17590.554700000001 15488.953100000001 0.000000000000 5704.087400000000 1757.230100000000 55449.925799999997 -4219.336430000000 -1447.543460000000 -5704.087400000000 0.000000000000 17590.554700000001 -4219.336430000000 8274.423830000000 20 25 66 3833.000000000000 0.000000000000 0.000000000000 0.000000000000 12265.152300000000 -760.157288000000 0.000000000000 3833.000000000000 0.000000000000 -12265.152300000000 0.000000000000 -5130.100590000000 0.000000000000 0.000000000000 3833.000000000000 760.157288000000 5130.100590000000 0.000000000000 0.000000000000 -12265.152300000000 760.157288000000 40542.808599999997 953.621643000000 16416.232400000001 12265.152300000000 0.000000000000 5130.100590000000 953.621643000000 46340.835899999998 -2350.166500000000 -760.157288000000 -5130.100590000000 0.000000000000 16416.232400000001 -2350.166500000000 8091.116700000000 20 32 66 4517.000000000000 0.000000000000 0.000000000000 0.000000000000 13682.622100000001 -1158.520390000000 0.000000000000 4517.000000000000 0.000000000000 -13682.622100000001 0.000000000000 -6061.389160000000 0.000000000000 0.000000000000 4517.000000000000 1158.520390000000 6061.389160000000 0.000000000000 0.000000000000 -13682.622100000001 1158.520390000000 43300.511700000003 1417.239500000000 18500.168000000001 13682.622100000001 0.000000000000 6061.389160000000 1417.239500000000 50231.464800000002 -2919.536620000000 -1158.520390000000 -6061.389160000000 0.000000000000 18500.168000000001 -2919.536620000000 9504.740229999999 20 33 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14111.051799999999 -1326.548580000000 0.000000000000 5000.000000000000 0.000000000000 -14111.051799999999 0.000000000000 -4455.370610000000 0.000000000000 0.000000000000 5000.000000000000 1326.548580000000 4455.370610000000 0.000000000000 0.000000000000 -14111.051799999999 1326.548580000000 42845.164100000002 1590.294680000000 12535.321300000000 14111.051799999999 0.000000000000 4455.370610000000 1590.294680000000 46655.484400000001 -2984.344730000000 -1326.548580000000 -4455.370610000000 0.000000000000 12535.321300000000 -2984.344730000000 6417.236820000000 20 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8141.500490000000 -2490.204100000000 0.000000000000 5000.000000000000 0.000000000000 -8141.500490000000 0.000000000000 -2202.806880000000 0.000000000000 0.000000000000 5000.000000000000 2490.204100000000 2202.806880000000 0.000000000000 0.000000000000 -8141.500490000000 2490.204100000000 15286.062500000000 1260.187500000000 3443.039550000000 8141.500490000000 0.000000000000 2202.806880000000 1260.187500000000 15443.165999999999 -4014.882810000000 -2490.204100000000 -2202.806880000000 0.000000000000 3443.039550000000 -4014.882810000000 2938.505860000000 20 63 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14395.251000000000 -840.335876000000 0.000000000000 5000.000000000000 0.000000000000 -14395.251000000000 0.000000000000 4001.101070000000 0.000000000000 0.000000000000 5000.000000000000 840.335876000000 -4001.101070000000 0.000000000000 0.000000000000 -14395.251000000000 840.335876000000 43741.226600000002 -514.057007000000 -11570.450199999999 14395.251000000000 0.000000000000 -4001.101070000000 -514.057007000000 46187.371099999997 -1559.019170000000 -840.335876000000 4001.101070000000 0.000000000000 -11570.450199999999 -1559.019170000000 5005.248540000000 21 25 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16153.040999999999 -598.622192000000 0.000000000000 5000.000000000000 0.000000000000 -16153.040999999999 0.000000000000 -5907.458500000000 0.000000000000 0.000000000000 5000.000000000000 598.622192000000 5907.458500000000 0.000000000000 0.000000000000 -16153.040999999999 598.622192000000 53272.847699999998 708.558411000000 19095.820299999999 16153.040999999999 0.000000000000 5907.458500000000 708.558411000000 59470.835899999998 -1801.798950000000 -598.622192000000 -5907.458500000000 0.000000000000 19095.820299999999 -1801.798950000000 8058.118160000000 21 32 66 3968.000000000000 0.000000000000 0.000000000000 0.000000000000 11583.418000000000 -1311.949580000000 0.000000000000 3968.000000000000 0.000000000000 -11583.418000000000 0.000000000000 -4607.350590000000 0.000000000000 0.000000000000 3968.000000000000 1311.949580000000 4607.350590000000 0.000000000000 0.000000000000 -11583.418000000000 1311.949580000000 34950.703099999999 1466.762820000000 13596.074199999999 11583.418000000000 0.000000000000 4607.350590000000 1466.762820000000 39773.054700000001 -3607.963130000000 -1311.949580000000 -4607.350590000000 0.000000000000 13596.074199999999 -3607.963130000000 6380.312990000000 21 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8855.483399999999 -1509.099000000000 0.000000000000 5000.000000000000 0.000000000000 -8855.483399999999 0.000000000000 -592.407471000000 0.000000000000 0.000000000000 5000.000000000000 1509.099000000000 592.407471000000 0.000000000000 0.000000000000 -8855.483399999999 1509.099000000000 16978.380900000000 320.665833000000 1253.347660000000 8855.483399999999 0.000000000000 592.407471000000 320.665833000000 16797.654299999998 -2696.754880000000 -1509.099000000000 -592.407471000000 0.000000000000 1253.347660000000 -2696.754880000000 1058.985110000000 21 47 66 4487.000000000000 0.000000000000 0.000000000000 0.000000000000 8940.782230000001 -2432.310300000000 0.000000000000 4487.000000000000 0.000000000000 -8940.782230000001 0.000000000000 -3208.308590000000 0.000000000000 0.000000000000 4487.000000000000 2432.310300000000 3208.308590000000 0.000000000000 0.000000000000 -8940.782230000001 2432.310300000000 19720.152300000002 1717.025150000000 6650.069340000000 8940.782230000001 0.000000000000 3208.308590000000 1717.025150000000 21286.736300000000 -4920.086430000000 -2432.310300000000 -3208.308590000000 0.000000000000 6650.069340000000 -4920.086430000000 4333.045410000000 21 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9885.950199999999 -2480.989010000000 0.000000000000 5000.000000000000 0.000000000000 -9885.950199999999 0.000000000000 -2819.072750000000 0.000000000000 0.000000000000 5000.000000000000 2480.989010000000 2819.072750000000 0.000000000000 0.000000000000 -9885.950199999999 2480.989010000000 21628.095700000002 1470.749020000000 5982.152830000000 9885.950199999999 0.000000000000 2819.072750000000 1470.749020000000 22746.488300000001 -5014.775390000000 -2480.989010000000 -2819.072750000000 0.000000000000 5982.152830000000 -5014.775390000000 3744.013180000000 21 63 66 2348.000000000000 0.000000000000 0.000000000000 0.000000000000 7041.343260000000 -133.519684000000 0.000000000000 2348.000000000000 0.000000000000 -7041.343260000000 0.000000000000 2049.077880000000 0.000000000000 0.000000000000 2348.000000000000 133.519684000000 -2049.077880000000 0.000000000000 0.000000000000 -7041.343260000000 133.519684000000 21619.865200000000 -208.308319000000 -6093.212890000000 7041.343260000000 0.000000000000 -2049.077880000000 -208.308319000000 23262.189500000000 -208.023712000000 -133.519684000000 2049.077880000000 0.000000000000 -6093.212890000000 -208.023712000000 2277.678470000000 21 64 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15629.216800000000 621.108276000000 0.000000000000 5000.000000000000 0.000000000000 -15629.216800000000 0.000000000000 3271.867190000000 0.000000000000 0.000000000000 5000.000000000000 -621.108276000000 -3271.867190000000 0.000000000000 0.000000000000 -15629.216800000000 -621.108276000000 50413.839800000002 -203.655182000000 -10064.340800000000 15629.216800000000 0.000000000000 -3271.867190000000 -203.655182000000 52873.621099999997 2329.052730000000 621.108276000000 3271.867190000000 0.000000000000 -10064.340800000000 2329.052730000000 4502.244140000000 21 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16300.049800000001 19.035057100000 0.000000000000 5000.000000000000 0.000000000000 -16300.049800000001 0.000000000000 -914.403381000000 0.000000000000 0.000000000000 5000.000000000000 -19.035057100000 914.403381000000 0.000000000000 0.000000000000 -16300.049800000001 -19.035057100000 54126.460899999998 290.748322000000 2945.648440000000 16300.049800000001 0.000000000000 914.403381000000 290.748322000000 55442.574200000003 149.614746000000 19.035057100000 -914.403381000000 0.000000000000 2945.648440000000 149.614746000000 2932.442380000000 22 25 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15932.630900000000 -2285.753420000000 0.000000000000 5000.000000000000 0.000000000000 -15932.630900000000 0.000000000000 -4233.381840000000 0.000000000000 0.000000000000 5000.000000000000 2285.753420000000 4233.381840000000 0.000000000000 0.000000000000 -15932.630900000000 2285.753420000000 52699.277300000002 2012.174800000000 13474.780300000000 15932.630900000000 0.000000000000 4233.381840000000 2012.174800000000 55077.667999999998 -7141.472170000000 -2285.753420000000 -4233.381840000000 0.000000000000 13474.780300000000 -7141.472170000000 5747.564450000000 22 26 66 3110.000000000000 0.000000000000 0.000000000000 0.000000000000 10076.784200000000 -824.964172000000 0.000000000000 3110.000000000000 0.000000000000 -10076.784200000000 0.000000000000 -3096.577880000000 0.000000000000 0.000000000000 3110.000000000000 824.964172000000 3096.577880000000 0.000000000000 0.000000000000 -10076.784200000000 824.964172000000 33752.125000000000 1036.151370000000 10029.511699999999 10076.784200000000 0.000000000000 3096.577880000000 1036.151370000000 36071.964800000002 -2597.848880000000 -824.964172000000 -3096.577880000000 0.000000000000 10029.511699999999 -2597.848880000000 4356.730960000000 22 27 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15633.152300000000 -2116.155520000000 0.000000000000 5000.000000000000 0.000000000000 -15633.152300000000 0.000000000000 -5401.710940000000 0.000000000000 0.000000000000 5000.000000000000 2116.155520000000 5401.710940000000 0.000000000000 0.000000000000 -15633.152300000000 2116.155520000000 50931.875000000000 2585.004640000000 16830.488300000001 15633.152300000000 0.000000000000 5401.710940000000 2585.004640000000 55328.757799999999 -6316.453610000000 -2116.155520000000 -5401.710940000000 0.000000000000 16830.488300000001 -6316.453610000000 7877.699220000000 22 32 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15290.677700000000 -2621.582520000000 0.000000000000 5000.000000000000 0.000000000000 -15290.677700000000 0.000000000000 -4591.788570000000 0.000000000000 0.000000000000 5000.000000000000 2621.582520000000 4591.788570000000 0.000000000000 0.000000000000 -15290.677700000000 2621.582520000000 49060.082000000002 2471.786620000000 14151.742200000001 15290.677700000000 0.000000000000 4591.788570000000 2471.786620000000 52008.082000000002 -7743.837400000000 -2621.582520000000 -4591.788570000000 0.000000000000 14151.742200000001 -7743.837400000000 6590.545900000000 22 35 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9431.401370000000 -2204.482670000000 0.000000000000 5000.000000000000 0.000000000000 -9431.401370000000 0.000000000000 2223.382080000000 0.000000000000 0.000000000000 5000.000000000000 2204.482670000000 -2223.382080000000 0.000000000000 0.000000000000 -9431.401370000000 2204.482670000000 19172.078099999999 -838.894043000000 -4091.961910000000 9431.401370000000 0.000000000000 -2223.382080000000 -838.894043000000 19385.701200000000 -4232.604980000000 -2204.482670000000 2223.382080000000 0.000000000000 -4091.961910000000 -4232.604980000000 2433.680180000000 22 48 66 3271.000000000000 0.000000000000 0.000000000000 0.000000000000 6519.772950000000 -2030.263790000000 0.000000000000 3271.000000000000 0.000000000000 -6519.772950000000 0.000000000000 229.541214000000 0.000000000000 0.000000000000 3271.000000000000 2030.263790000000 -229.541214000000 0.000000000000 0.000000000000 -6519.772950000000 2030.263790000000 14730.698200000001 -39.036865200000 -191.110855000000 6519.772950000000 0.000000000000 -229.541214000000 -39.036865200000 13842.893599999999 -4190.356930000000 -2030.263790000000 229.541214000000 0.000000000000 -191.110855000000 -4190.356930000000 1775.824710000000 22 64 66 3563.000000000000 0.000000000000 0.000000000000 0.000000000000 11628.873000000000 460.388123000000 0.000000000000 3563.000000000000 0.000000000000 -11628.873000000000 0.000000000000 2180.793950000000 0.000000000000 0.000000000000 3563.000000000000 -460.388123000000 -2180.793950000000 0.000000000000 0.000000000000 -11628.873000000000 -460.388123000000 38490.316400000003 115.961227000000 -7171.576170000000 11628.873000000000 0.000000000000 -2180.793950000000 115.961227000000 39884.984400000001 1444.574100000000 460.388123000000 2180.793950000000 0.000000000000 -7171.576170000000 1444.574100000000 2306.734130000000 23 26 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15575.509800000000 -5701.036620000000 0.000000000000 5000.000000000000 0.000000000000 -15575.509800000000 0.000000000000 -3319.184080000000 0.000000000000 0.000000000000 5000.000000000000 5701.036620000000 3319.184080000000 0.000000000000 0.000000000000 -15575.509800000000 5701.036620000000 56361.406300000002 3857.329350000000 10219.015600000001 15575.509800000000 0.000000000000 3319.184080000000 3857.329350000000 52524.132799999999 -17514.572300000000 -5701.036620000000 -3319.184080000000 0.000000000000 10219.015600000001 -17514.572300000000 11193.179700000001 23 28 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13624.252000000000 -6950.806150000000 0.000000000000 5000.000000000000 0.000000000000 -13624.252000000000 0.000000000000 -5957.137210000000 0.000000000000 0.000000000000 5000.000000000000 6950.806150000000 5957.137210000000 0.000000000000 0.000000000000 -13624.252000000000 6950.806150000000 47811.964800000002 8272.689450000000 16358.318400000000 13624.252000000000 0.000000000000 5957.137210000000 8272.689450000000 45374.968800000002 -18855.119100000000 -6950.806150000000 -5957.137210000000 0.000000000000 16358.318400000000 -18855.119100000000 17055.500000000000 23 31 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12549.573200000001 -7083.805660000000 0.000000000000 5000.000000000000 0.000000000000 -12549.573200000001 0.000000000000 -5802.390140000000 0.000000000000 0.000000000000 5000.000000000000 7083.805660000000 5802.390140000000 0.000000000000 0.000000000000 -12549.573200000001 7083.805660000000 41947.210899999998 8226.085940000001 14707.738300000001 12549.573200000001 0.000000000000 5802.390140000000 8226.085940000001 38920.406300000002 -17780.119100000000 -7083.805660000000 -5802.390140000000 0.000000000000 14707.738300000001 -17780.119100000000 17045.656299999999 23 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14224.195299999999 -5889.009280000000 0.000000000000 5000.000000000000 0.000000000000 -14224.195299999999 0.000000000000 3943.469480000000 0.000000000000 0.000000000000 5000.000000000000 5889.009280000000 -3943.469480000000 0.000000000000 0.000000000000 -14224.195299999999 5889.009280000000 48563.035199999998 -4461.073730000000 -11608.796899999999 14224.195299999999 0.000000000000 -3943.469480000000 -4461.073730000000 44916.289100000002 -16473.119100000000 -5889.009280000000 3943.469480000000 0.000000000000 -11608.796899999999 -16473.119100000000 11106.426799999999 23 64 66 4403.000000000000 0.000000000000 0.000000000000 0.000000000000 13069.464800000000 -4379.874510000000 0.000000000000 4403.000000000000 0.000000000000 -13069.464800000000 0.000000000000 4110.628420000000 0.000000000000 0.000000000000 4403.000000000000 4379.874510000000 -4110.628420000000 0.000000000000 0.000000000000 -13069.464800000000 4379.874510000000 44202.710899999998 -4161.750980000000 -12270.716800000000 13069.464800000000 0.000000000000 -4110.628420000000 -4161.750980000000 43215.062500000000 -12712.223599999999 -4379.874510000000 4110.628420000000 0.000000000000 -12270.716800000000 -12712.223599999999 9147.480470000000 24 28 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13810.088900000001 -2743.735600000000 0.000000000000 5000.000000000000 0.000000000000 -13810.088900000001 0.000000000000 -4915.175290000000 0.000000000000 0.000000000000 5000.000000000000 2743.735600000000 4915.175290000000 0.000000000000 0.000000000000 -13810.088900000001 2743.735600000000 40800.085899999998 2541.565190000000 13654.955099999999 13810.088900000001 0.000000000000 4915.175290000000 2541.565190000000 44366.347699999998 -7287.178220000000 -2743.735600000000 -4915.175290000000 0.000000000000 13654.955099999999 -7287.178220000000 7119.801270000000 24 29 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12816.108399999999 -2528.903560000000 0.000000000000 5000.000000000000 0.000000000000 -12816.108399999999 0.000000000000 -6051.351070000000 0.000000000000 0.000000000000 5000.000000000000 2528.903560000000 6051.351070000000 0.000000000000 0.000000000000 -12816.108399999999 2528.903560000000 35064.511700000003 2887.209960000000 15593.006799999999 12816.108399999999 0.000000000000 6051.351070000000 2887.209960000000 41003.886700000003 -6312.317380000000 -2528.903560000000 -6051.351070000000 0.000000000000 15593.006799999999 -6312.317380000000 9114.230470000000 24 31 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13339.723599999999 -2929.776860000000 0.000000000000 5000.000000000000 0.000000000000 -13339.723599999999 0.000000000000 -4773.795410000000 0.000000000000 0.000000000000 5000.000000000000 2929.776860000000 4773.795410000000 0.000000000000 0.000000000000 -13339.723599999999 2929.776860000000 38236.136700000003 2524.709230000000 13044.456099999999 13339.723599999999 0.000000000000 4773.795410000000 2524.709230000000 41547.843800000002 -7602.306640000000 -2929.776860000000 -4773.795410000000 0.000000000000 13044.456099999999 -7602.306640000000 7180.991210000000 24 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13011.939500000000 -3193.702880000000 0.000000000000 5000.000000000000 0.000000000000 -13011.939500000000 0.000000000000 4434.372070000000 0.000000000000 0.000000000000 5000.000000000000 3193.702880000000 -4434.372070000000 0.000000000000 0.000000000000 -13011.939500000000 3193.702880000000 36515.355499999998 -2671.468990000000 -11776.047900000000 13011.939500000000 0.000000000000 -4434.372070000000 -2671.468990000000 38604.351600000002 -8166.543460000000 -3193.702880000000 4434.372070000000 0.000000000000 -11776.047900000000 -8166.543460000000 6622.177250000000 24 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14046.160200000000 -2511.823240000000 0.000000000000 5000.000000000000 0.000000000000 -14046.160200000000 0.000000000000 4100.771480000000 0.000000000000 0.000000000000 5000.000000000000 2511.823240000000 -4100.771480000000 0.000000000000 0.000000000000 -14046.160200000000 2511.823240000000 41690.746099999997 -1866.973390000000 -11462.007799999999 14046.160200000000 0.000000000000 -4100.771480000000 -1866.973390000000 43497.753900000003 -6832.222660000000 -2511.823240000000 4100.771480000000 0.000000000000 -11462.007799999999 -6832.222660000000 5593.664550000000 25 29 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13885.480500000000 -678.802490000000 0.000000000000 5000.000000000000 0.000000000000 -13885.480500000000 0.000000000000 -5057.533690000000 0.000000000000 0.000000000000 5000.000000000000 678.802490000000 5057.533690000000 0.000000000000 0.000000000000 -13885.480500000000 678.802490000000 40648.187500000000 296.794159000000 14551.517599999999 13885.480500000000 0.000000000000 5057.533690000000 296.794159000000 45519.242200000001 -1209.146850000000 -678.802490000000 -5057.533690000000 0.000000000000 14551.517599999999 -1209.146850000000 6115.206050000000 25 31 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13064.552700000000 -1746.998170000000 0.000000000000 5000.000000000000 0.000000000000 -13064.552700000000 0.000000000000 -3685.639650000000 0.000000000000 0.000000000000 5000.000000000000 1746.998170000000 3685.639650000000 0.000000000000 0.000000000000 -13064.552700000000 1746.998170000000 36468.996099999997 658.231628000000 10217.319299999999 13064.552700000000 0.000000000000 3685.639650000000 658.231628000000 38805.078099999999 -3962.113280000000 -1746.998170000000 -3685.639650000000 0.000000000000 10217.319299999999 -3962.113280000000 4797.485350000000 26 28 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12870.773400000000 -4763.681150000000 0.000000000000 5000.000000000000 0.000000000000 -12870.773400000000 0.000000000000 -1032.266240000000 0.000000000000 0.000000000000 5000.000000000000 4763.681150000000 1032.266240000000 0.000000000000 0.000000000000 -12870.773400000000 4763.681150000000 39107.472699999998 817.318604000000 2678.767820000000 12870.773400000000 0.000000000000 1032.266240000000 817.318604000000 35382.960899999998 -12114.569299999999 -4763.681150000000 -1032.266240000000 0.000000000000 2678.767820000000 -12114.569299999999 6011.150390000000 26 33 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13637.013700000000 -3385.801030000000 0.000000000000 5000.000000000000 0.000000000000 -13637.013700000000 0.000000000000 3701.243650000000 0.000000000000 0.000000000000 5000.000000000000 3385.801030000000 -3701.243650000000 0.000000000000 0.000000000000 -13637.013700000000 3385.801030000000 41708.500000000000 -2307.608150000000 -10228.903300000000 13637.013700000000 0.000000000000 -3701.243650000000 -2307.608150000000 41907.273399999998 -8550.500000000000 -3385.801030000000 3701.243650000000 0.000000000000 -10228.903300000000 -8550.500000000000 7011.106930000000 27 29 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9469.948240000000 -2325.139650000000 0.000000000000 5000.000000000000 0.000000000000 -9469.948240000000 0.000000000000 -4091.252930000000 0.000000000000 0.000000000000 5000.000000000000 2325.139650000000 4091.252930000000 0.000000000000 0.000000000000 -9469.948240000000 2325.139650000000 21653.230500000001 1436.662110000000 8257.556640000001 9469.948240000000 0.000000000000 4091.252930000000 1436.662110000000 23688.287100000001 -3410.099850000000 -2325.139650000000 -4091.252930000000 0.000000000000 8257.556640000001 -3410.099850000000 5792.910160000000 27 30 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7594.247560000000 -3121.682130000000 0.000000000000 5000.000000000000 0.000000000000 -7594.247560000000 0.000000000000 -3915.667720000000 0.000000000000 0.000000000000 5000.000000000000 3121.682130000000 3915.667720000000 0.000000000000 0.000000000000 -7594.247560000000 3121.682130000000 14263.549800000001 2199.424320000000 5997.651860000000 7594.247560000000 0.000000000000 3915.667720000000 2199.424320000000 15349.184600000001 -4508.825680000000 -3121.682130000000 -3915.667720000000 0.000000000000 5997.651860000000 -4508.825680000000 5986.828130000000 27 31 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9595.737300000001 -2469.595700000000 0.000000000000 5000.000000000000 0.000000000000 -9595.737300000001 0.000000000000 -3232.410890000000 0.000000000000 0.000000000000 5000.000000000000 2469.595700000000 3232.410890000000 0.000000000000 0.000000000000 -9595.737300000001 2469.595700000000 21807.125000000000 840.850769000000 6481.220700000000 9595.737300000001 0.000000000000 3232.410890000000 840.850769000000 23244.455099999999 -4107.348140000000 -2469.595700000000 -3232.410890000000 0.000000000000 6481.220700000000 -4107.348140000000 5474.973630000000 28 33 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13462.770500000001 961.610107000000 0.000000000000 5000.000000000000 0.000000000000 -13462.770500000001 0.000000000000 4679.880860000000 0.000000000000 0.000000000000 5000.000000000000 -961.610107000000 -4679.880860000000 0.000000000000 0.000000000000 -13462.770500000001 -961.610107000000 38524.281300000002 1217.461790000000 -12956.791999999999 13462.770500000001 0.000000000000 -4679.880860000000 1217.461790000000 41889.554700000001 3370.439940000000 961.610107000000 4679.880860000000 0.000000000000 -12956.791999999999 3370.439940000000 5901.769040000000 30 32 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10368.831099999999 1040.974240000000 0.000000000000 5000.000000000000 0.000000000000 -10368.831099999999 0.000000000000 5849.797850000000 0.000000000000 0.000000000000 5000.000000000000 -1040.974240000000 -5849.797850000000 0.000000000000 0.000000000000 -10368.831099999999 -1040.974240000000 22778.130900000000 1399.828250000000 -12135.636699999999 10368.831099999999 0.000000000000 -5849.797850000000 1399.828250000000 28744.019499999999 2439.631840000000 1040.974240000000 5849.797850000000 0.000000000000 -12135.636699999999 2439.631840000000 8138.804690000000 33 34 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10598.762699999999 -1415.373780000000 0.000000000000 5000.000000000000 0.000000000000 -10598.762699999999 0.000000000000 5762.909180000000 0.000000000000 0.000000000000 5000.000000000000 1415.373780000000 -5762.909180000000 0.000000000000 0.000000000000 -10598.762699999999 1415.373780000000 26009.353500000001 -1670.460820000000 -12194.224600000000 10598.762699999999 0.000000000000 -5762.909180000000 -1670.460820000000 31401.968799999999 -1914.927250000000 -1415.373780000000 5762.909180000000 0.000000000000 -12194.224600000000 -1914.927250000000 8657.456050000001 33 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13626.931600000000 987.679504000000 0.000000000000 5000.000000000000 0.000000000000 -13626.931600000000 0.000000000000 4672.532230000000 0.000000000000 0.000000000000 5000.000000000000 -987.679504000000 -4672.532230000000 0.000000000000 0.000000000000 -13626.931600000000 -987.679504000000 39562.398399999998 796.484619000000 -12756.796899999999 13626.931600000000 0.000000000000 -4672.532230000000 796.484619000000 42513.093800000002 3323.306150000000 987.679504000000 4672.532230000000 0.000000000000 -12756.796899999999 3323.306150000000 6906.421880000000 34 36 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8573.805660000000 -1472.771480000000 0.000000000000 5000.000000000000 0.000000000000 -8573.805660000000 0.000000000000 4021.390140000000 0.000000000000 0.000000000000 5000.000000000000 1472.771480000000 -4021.390140000000 0.000000000000 0.000000000000 -8573.805660000000 1472.771480000000 16049.798800000000 -1251.477540000000 -6647.377440000000 8573.805660000000 0.000000000000 -4021.390140000000 -1251.477540000000 18795.013700000000 -2283.781490000000 -1472.771480000000 4021.390140000000 0.000000000000 -6647.377440000000 -2283.781490000000 4738.414060000000 34 37 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8503.793949999999 -1518.066040000000 0.000000000000 5000.000000000000 0.000000000000 -8503.793949999999 0.000000000000 4092.354740000000 0.000000000000 0.000000000000 5000.000000000000 1518.066040000000 -4092.354740000000 0.000000000000 0.000000000000 -8503.793949999999 1518.066040000000 15734.914100000000 -1203.214230000000 -6840.041500000000 8503.793949999999 0.000000000000 -4092.354740000000 -1203.214230000000 18420.892599999999 -2402.814940000000 -1518.066040000000 4092.354740000000 0.000000000000 -6840.041500000000 -2402.814940000000 4709.463380000000 34 38 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7942.638670000000 -2187.430910000000 0.000000000000 5000.000000000000 0.000000000000 -7942.638670000000 0.000000000000 5088.380370000000 0.000000000000 0.000000000000 5000.000000000000 2187.430910000000 -5088.380370000000 0.000000000000 0.000000000000 -7942.638670000000 2187.430910000000 14192.345700000000 -2211.063960000000 -8042.889650000000 7942.638670000000 0.000000000000 -5088.380370000000 -2211.063960000000 18166.912100000001 -3394.324220000000 -2187.430910000000 5088.380370000000 0.000000000000 -8042.889650000000 -3394.324220000000 6845.676270000000 34 46 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8079.147460000000 -2187.834230000000 0.000000000000 5000.000000000000 0.000000000000 -8079.147460000000 0.000000000000 4410.866700000000 0.000000000000 0.000000000000 5000.000000000000 2187.834230000000 -4410.866700000000 0.000000000000 0.000000000000 -8079.147460000000 2187.834230000000 14531.293000000000 -1827.827270000000 -7100.426760000000 8079.147460000000 0.000000000000 -4410.866700000000 -1827.827270000000 17454.152300000002 -3517.685300000000 -2187.834230000000 4410.866700000000 0.000000000000 -7100.426760000000 -3517.685300000000 5575.972170000000 34 47 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8268.622069999999 -2019.585820000000 0.000000000000 5000.000000000000 0.000000000000 -8268.622069999999 0.000000000000 3579.372310000000 0.000000000000 0.000000000000 5000.000000000000 2019.585820000000 -3579.372310000000 0.000000000000 0.000000000000 -8268.622069999999 2019.585820000000 14977.871100000000 -1126.113890000000 -5862.016600000000 8268.622069999999 0.000000000000 -3579.372310000000 -1126.113890000000 17276.656299999999 -3365.797120000000 -2019.585820000000 3579.372310000000 0.000000000000 -5862.016600000000 -3365.797120000000 4597.839840000000 34 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8579.778319999999 -1788.080570000000 0.000000000000 5000.000000000000 0.000000000000 -8579.778319999999 0.000000000000 3207.835690000000 0.000000000000 0.000000000000 5000.000000000000 1788.080570000000 -3207.835690000000 0.000000000000 0.000000000000 -8579.778319999999 1788.080570000000 15960.825199999999 -811.602539000000 -5241.733890000000 8579.778319999999 0.000000000000 -3207.835690000000 -811.602539000000 18276.789100000002 -3091.405270000000 -1788.080570000000 3207.835690000000 0.000000000000 -5241.733890000000 -3091.405270000000 4254.411130000000 34 49 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8663.168949999999 -1257.488400000000 0.000000000000 5000.000000000000 0.000000000000 -8663.168949999999 0.000000000000 3498.288570000000 0.000000000000 0.000000000000 5000.000000000000 1257.488400000000 -3498.288570000000 0.000000000000 0.000000000000 -8663.168949999999 1257.488400000000 16016.775400000000 -772.419067000000 -5850.166500000000 8663.168949999999 0.000000000000 -3498.288570000000 -772.419067000000 18457.947300000000 -2088.567380000000 -1257.488400000000 3498.288570000000 0.000000000000 -5850.166500000000 -2088.567380000000 3821.661130000000 34 63 66 3397.000000000000 0.000000000000 0.000000000000 0.000000000000 11135.852500000001 3113.095210000000 0.000000000000 3397.000000000000 0.000000000000 -11135.852500000001 0.000000000000 -1767.499270000000 0.000000000000 0.000000000000 3397.000000000000 -3113.095210000000 1767.499270000000 0.000000000000 0.000000000000 -11135.852500000001 -3113.095210000000 39814.363299999997 -1659.514040000000 5807.161130000000 11135.852500000001 0.000000000000 1767.499270000000 -1659.514040000000 37602.664100000002 10279.251000000000 3113.095210000000 -1767.499270000000 0.000000000000 5807.161130000000 10279.251000000000 4282.231930000000 34 64 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15406.098599999999 1928.273680000000 0.000000000000 5000.000000000000 0.000000000000 -15406.098599999999 0.000000000000 -2510.844730000000 0.000000000000 0.000000000000 5000.000000000000 -1928.273680000000 2510.844730000000 0.000000000000 0.000000000000 -15406.098599999999 -1928.273680000000 49938.914100000002 -1411.430050000000 7634.434080000000 15406.098599999999 0.000000000000 2510.844730000000 -1411.430050000000 49913.218800000002 6269.429690000000 1928.273680000000 -2510.844730000000 0.000000000000 7634.434080000000 6269.429690000000 4031.085450000000 35 39 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9930.100590000000 -2389.187990000000 0.000000000000 5000.000000000000 0.000000000000 -9930.100590000000 0.000000000000 5593.892090000000 0.000000000000 0.000000000000 5000.000000000000 2389.187990000000 -5593.892090000000 0.000000000000 0.000000000000 -9930.100590000000 2389.187990000000 21477.054700000001 -2673.238040000000 -11247.580099999999 9930.100590000000 0.000000000000 -5593.892090000000 -2673.238040000000 26740.679700000001 -4577.516110000000 -2389.187990000000 5593.892090000000 0.000000000000 -11247.580099999999 -4577.516110000000 7916.371090000000 35 44 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9330.356449999999 -2099.878420000000 0.000000000000 5000.000000000000 0.000000000000 -9330.356449999999 0.000000000000 5109.238770000000 0.000000000000 0.000000000000 5000.000000000000 2099.878420000000 -5109.238770000000 0.000000000000 0.000000000000 -9330.356449999999 2099.878420000000 18840.431600000000 -2418.693850000000 -9626.655269999999 9330.356449999999 0.000000000000 -5109.238770000000 -2418.693850000000 23351.285199999998 -3872.890870000000 -2099.878420000000 5109.238770000000 0.000000000000 -9626.655269999999 -3872.890870000000 6897.129390000000 35 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9807.518550000001 -1220.723880000000 0.000000000000 5000.000000000000 0.000000000000 -9807.518550000001 0.000000000000 4215.566890000000 0.000000000000 0.000000000000 5000.000000000000 1220.723880000000 -4215.566890000000 0.000000000000 0.000000000000 -9807.518550000001 1220.723880000000 21873.220700000002 -1614.639040000000 -8176.781740000000 9807.518550000001 0.000000000000 -4215.566890000000 -1614.639040000000 25072.355500000001 -1382.965210000000 -1220.723880000000 4215.566890000000 0.000000000000 -8176.781740000000 -1382.965210000000 6417.918460000000 35 51 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14580.360400000000 1081.055300000000 0.000000000000 5000.000000000000 0.000000000000 -14580.360400000000 0.000000000000 4839.427730000000 0.000000000000 0.000000000000 5000.000000000000 -1081.055300000000 -4839.427730000000 0.000000000000 0.000000000000 -14580.360400000000 -1081.055300000000 45182.570299999999 1041.710330000000 -15301.198200000001 14580.360400000000 0.000000000000 -4839.427730000000 1041.710330000000 50369.636700000003 3428.111080000000 1081.055300000000 4839.427730000000 0.000000000000 -15301.198200000001 3428.111080000000 6506.453130000000 35 52 66 4776.000000000000 0.000000000000 0.000000000000 0.000000000000 14254.323200000001 223.276749000000 0.000000000000 4776.000000000000 0.000000000000 -14254.323200000001 0.000000000000 6094.460450000000 0.000000000000 0.000000000000 4776.000000000000 -223.276749000000 -6094.460450000000 0.000000000000 0.000000000000 -14254.323200000001 -223.276749000000 43812.007799999999 76.404151900000 -18424.287100000001 14254.323200000001 0.000000000000 -6094.460450000000 76.404151900000 51835.136700000003 931.684509000000 223.276749000000 6094.460450000000 0.000000000000 -18424.287100000001 931.684509000000 8612.506840000000 36 44 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10832.429700000001 -1446.914060000000 0.000000000000 5000.000000000000 0.000000000000 -10832.429700000001 0.000000000000 3160.928960000000 0.000000000000 0.000000000000 5000.000000000000 1446.914060000000 -3160.928960000000 0.000000000000 0.000000000000 -10832.429700000001 1446.914060000000 24745.867200000001 -1144.518800000000 -7014.604980000000 10832.429700000001 0.000000000000 -3160.928960000000 -1144.518800000000 26743.162100000001 -2997.225590000000 -1446.914060000000 3160.928960000000 0.000000000000 -7014.604980000000 -2997.225590000000 3447.667720000000 36 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10533.348599999999 -1288.549440000000 0.000000000000 5000.000000000000 0.000000000000 -10533.348599999999 0.000000000000 2610.390140000000 0.000000000000 0.000000000000 5000.000000000000 1288.549440000000 -2610.390140000000 0.000000000000 0.000000000000 -10533.348599999999 1288.549440000000 23078.972699999998 -1269.846560000000 -5536.494630000000 10533.348599999999 0.000000000000 -2610.390140000000 -1269.846560000000 25749.443400000000 -2611.502690000000 -1288.549440000000 2610.390140000000 0.000000000000 -5536.494630000000 -2611.502690000000 4165.745120000000 36 51 66 4987.000000000000 0.000000000000 0.000000000000 0.000000000000 14050.578100000001 809.295044000000 0.000000000000 4987.000000000000 0.000000000000 -14050.578100000001 0.000000000000 2778.548340000000 0.000000000000 0.000000000000 4987.000000000000 -809.295044000000 -2778.548340000000 0.000000000000 0.000000000000 -14050.578100000001 -809.295044000000 41384.984400000001 537.696350000000 -9151.794920000000 14050.578100000001 0.000000000000 -2778.548340000000 537.696350000000 44735.921900000001 2309.915530000000 809.295044000000 2778.548340000000 0.000000000000 -9151.794920000000 2309.915530000000 4047.815670000000 36 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15485.259800000000 635.278076000000 0.000000000000 5000.000000000000 0.000000000000 -15485.259800000000 0.000000000000 4918.905270000000 0.000000000000 0.000000000000 5000.000000000000 -635.278076000000 -4918.905270000000 0.000000000000 0.000000000000 -15485.259800000000 -635.278076000000 48696.964800000002 680.458008000000 -15504.343800000001 15485.259800000000 0.000000000000 -4918.905270000000 680.458008000000 53917.027300000002 1976.624760000000 635.278076000000 4918.905270000000 0.000000000000 -15504.343800000001 1976.624760000000 5986.443360000000 36 53 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15568.914100000000 762.637939000000 0.000000000000 5000.000000000000 0.000000000000 -15568.914100000000 0.000000000000 5541.428710000000 0.000000000000 0.000000000000 5000.000000000000 -762.637939000000 -5541.428710000000 0.000000000000 0.000000000000 -15568.914100000000 -762.637939000000 49258.296900000001 997.298157000000 -17257.171900000001 15568.914100000000 0.000000000000 -5541.428710000000 997.298157000000 55137.441400000003 2478.714110000000 762.637939000000 5541.428710000000 0.000000000000 -17257.171900000001 2478.714110000000 6948.885250000000 37 44 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11672.169900000001 -1066.176880000000 0.000000000000 5000.000000000000 0.000000000000 -11672.169900000001 0.000000000000 3182.115230000000 0.000000000000 0.000000000000 5000.000000000000 1066.176880000000 -3182.115230000000 0.000000000000 0.000000000000 -11672.169900000001 1066.176880000000 28551.591799999998 -730.104980000000 -7561.114260000000 11672.169900000001 0.000000000000 -3182.115230000000 -730.104980000000 30723.259800000000 -2257.402830000000 -1066.176880000000 3182.115230000000 0.000000000000 -7561.114260000000 -2257.402830000000 3274.001710000000 37 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10915.504900000000 -544.874084000000 0.000000000000 5000.000000000000 0.000000000000 -10915.504900000000 0.000000000000 2504.252200000000 0.000000000000 0.000000000000 5000.000000000000 544.874084000000 -2504.252200000000 0.000000000000 0.000000000000 -10915.504900000000 544.874084000000 24565.556600000000 -581.901428000000 -5672.159180000000 10915.504900000000 0.000000000000 -2504.252200000000 -581.901428000000 27476.984400000001 -1124.291260000000 -544.874084000000 2504.252200000000 0.000000000000 -5672.159180000000 -1124.291260000000 3980.297360000000 37 51 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14101.629900000000 1167.717040000000 0.000000000000 5000.000000000000 0.000000000000 -14101.629900000000 0.000000000000 2095.894040000000 0.000000000000 0.000000000000 5000.000000000000 -1167.717040000000 -2095.894040000000 0.000000000000 0.000000000000 -14101.629900000000 -1167.717040000000 41743.191400000003 552.933105000000 -7229.576660000000 14101.629900000000 0.000000000000 -2095.894040000000 552.933105000000 44192.812500000000 3320.293210000000 1167.717040000000 2095.894040000000 0.000000000000 -7229.576660000000 3320.293210000000 3466.733150000000 37 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15810.857400000001 956.668945000000 0.000000000000 5000.000000000000 0.000000000000 -15810.857400000001 0.000000000000 4005.311280000000 0.000000000000 0.000000000000 5000.000000000000 -956.668945000000 -4005.311280000000 0.000000000000 0.000000000000 -15810.857400000001 -956.668945000000 50899.476600000002 929.967590000000 -12861.485400000000 15810.857400000001 0.000000000000 -4005.311280000000 929.967590000000 54137.261700000003 3029.988530000000 956.668945000000 4005.311280000000 0.000000000000 -12861.485400000000 3029.988530000000 4428.783200000000 37 53 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15870.587900000000 1651.974000000000 0.000000000000 5000.000000000000 0.000000000000 -15870.587900000000 0.000000000000 5038.628420000000 0.000000000000 0.000000000000 5000.000000000000 -1651.974000000000 -5038.628420000000 0.000000000000 0.000000000000 -15870.587900000000 -1651.974000000000 51867.910199999998 1953.054440000000 -16071.019500000000 15870.587900000000 0.000000000000 -5038.628420000000 1953.054440000000 56046.566400000003 5272.969730000000 1651.974000000000 5038.628420000000 0.000000000000 -16071.019500000000 5272.969730000000 6719.416990000000 38 40 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8690.415040000000 -1313.567870000000 0.000000000000 5000.000000000000 0.000000000000 -8690.415040000000 0.000000000000 5713.168950000000 0.000000000000 0.000000000000 5000.000000000000 1313.567870000000 -5713.168950000000 0.000000000000 0.000000000000 -8690.415040000000 1313.567870000000 16171.035200000000 -1350.090090000000 -9915.707030000000 8690.415040000000 0.000000000000 -5713.168950000000 -1350.090090000000 22053.697300000000 -2150.937260000000 -1313.567870000000 5713.168950000000 0.000000000000 -9915.707030000000 -2150.937260000000 7449.554690000000 38 43 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 8511.844730000001 -1849.726810000000 0.000000000000 5000.000000000000 0.000000000000 -8511.844730000001 0.000000000000 5440.554200000000 0.000000000000 0.000000000000 5000.000000000000 1849.726810000000 -5440.554200000000 0.000000000000 0.000000000000 -8511.844730000001 1849.726810000000 15611.503900000000 -1927.745360000000 -9187.694340000000 8511.844730000001 0.000000000000 -5440.554200000000 -1927.745360000000 20774.621100000000 -3140.139400000000 -1849.726810000000 5440.554200000000 0.000000000000 -9187.694340000000 -3140.139400000000 7025.799800000000 38 51 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13080.882799999999 1829.001340000000 0.000000000000 5000.000000000000 0.000000000000 -13080.882799999999 0.000000000000 1496.802120000000 0.000000000000 0.000000000000 5000.000000000000 -1829.001340000000 -1496.802120000000 0.000000000000 0.000000000000 -13080.882799999999 -1829.001340000000 36779.820299999999 1338.266850000000 -4968.883790000000 13080.882799999999 0.000000000000 -1496.802120000000 1338.266850000000 37814.945299999999 5165.063480000000 1829.001340000000 1496.802120000000 0.000000000000 -4968.883790000000 5165.063480000000 3893.756840000000 38 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14983.229499999999 3287.709230000000 0.000000000000 5000.000000000000 0.000000000000 -14983.229499999999 0.000000000000 3573.852290000000 0.000000000000 0.000000000000 5000.000000000000 -3287.709230000000 -3573.852290000000 0.000000000000 0.000000000000 -14983.229499999999 -3287.709230000000 48890.796900000001 3172.816650000000 -10802.095700000000 14983.229499999999 0.000000000000 -3573.852290000000 3172.816650000000 49049.152300000002 9687.717769999999 3287.709230000000 3573.852290000000 0.000000000000 -10802.095700000000 9687.717769999999 7238.868160000000 39 41 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 6952.539550000000 -794.359070000000 0.000000000000 5000.000000000000 0.000000000000 -6952.539550000000 0.000000000000 6203.638670000000 0.000000000000 0.000000000000 5000.000000000000 794.359070000000 -6203.638670000000 0.000000000000 0.000000000000 -6952.539550000000 794.359070000000 11273.304700000001 -956.073364000000 -8544.294920000000 6952.539550000000 0.000000000000 -6203.638670000000 -956.073364000000 17883.277300000002 -607.669006000000 -794.359070000000 6203.638670000000 0.000000000000 -8544.294920000000 -607.669006000000 9030.150390000001 39 42 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 7648.172850000000 -1070.496700000000 0.000000000000 5000.000000000000 0.000000000000 -7648.172850000000 0.000000000000 5382.552730000000 0.000000000000 0.000000000000 5000.000000000000 1070.496700000000 -5382.552730000000 0.000000000000 0.000000000000 -7648.172850000000 1070.496700000000 13452.283200000000 -1178.135500000000 -8023.188480000000 7648.172850000000 0.000000000000 -5382.552730000000 -1178.135500000000 18200.193400000000 -1230.681640000000 -1070.496700000000 5382.552730000000 0.000000000000 -8023.188480000000 -1230.681640000000 7390.449710000000 39 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9736.272460000000 -2622.973630000000 0.000000000000 5000.000000000000 0.000000000000 -9736.272460000000 0.000000000000 367.723907000000 0.000000000000 0.000000000000 5000.000000000000 2622.973630000000 -367.723907000000 0.000000000000 0.000000000000 -9736.272460000000 2622.973630000000 20943.714800000002 -270.686829000000 -377.919098000000 9736.272460000000 0.000000000000 -367.723907000000 -270.686829000000 20565.287100000001 -4967.713380000000 -2622.973630000000 367.723907000000 0.000000000000 -377.919098000000 -4967.713380000000 2750.953120000000 39 49 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11293.974600000000 -1188.978880000000 0.000000000000 5000.000000000000 0.000000000000 -11293.974600000000 0.000000000000 -855.060364000000 0.000000000000 0.000000000000 5000.000000000000 1188.978880000000 855.060364000000 0.000000000000 0.000000000000 -11293.974600000000 1188.978880000000 26767.562500000000 438.225861000000 1931.205440000000 11293.974600000000 0.000000000000 855.060364000000 438.225861000000 26615.914100000002 -2378.791500000000 -1188.978880000000 -855.060364000000 0.000000000000 1931.205440000000 -2378.791500000000 1573.304690000000 39 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12254.600600000000 -390.836731000000 0.000000000000 5000.000000000000 0.000000000000 -12254.600600000000 0.000000000000 -1402.299440000000 0.000000000000 0.000000000000 5000.000000000000 390.836731000000 1402.299440000000 0.000000000000 0.000000000000 -12254.600600000000 390.836731000000 31359.390599999999 180.741104000000 3447.858640000000 12254.600600000000 0.000000000000 1402.299440000000 180.741104000000 31231.261699999999 -559.306335000000 -390.836731000000 -1402.299440000000 0.000000000000 3447.858640000000 -559.306335000000 1614.041140000000 39 51 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14763.252000000000 974.444519000000 0.000000000000 5000.000000000000 0.000000000000 -14763.252000000000 0.000000000000 -4212.493160000000 0.000000000000 0.000000000000 5000.000000000000 -974.444519000000 4212.493160000000 0.000000000000 0.000000000000 -14763.252000000000 -974.444519000000 44916.742200000001 -551.218201000000 12697.394500000000 14763.252000000000 0.000000000000 4212.493160000000 -551.218201000000 48207.648399999998 2895.718750000000 974.444519000000 -4212.493160000000 0.000000000000 12697.394500000000 2895.718750000000 5067.342770000000 39 52 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15546.728499999999 1104.766850000000 0.000000000000 5000.000000000000 0.000000000000 -15546.728499999999 0.000000000000 -4584.871580000000 0.000000000000 0.000000000000 5000.000000000000 -1104.766850000000 4584.871580000000 0.000000000000 0.000000000000 -15546.728499999999 -1104.766850000000 49921.578099999999 -658.034058000000 14338.545899999999 15546.728499999999 0.000000000000 4584.871580000000 -658.034058000000 53175.851600000002 3501.694580000000 1104.766850000000 -4584.871580000000 0.000000000000 14338.545899999999 3501.694580000000 5990.623050000000 39 53 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15911.617200000001 2669.896000000000 0.000000000000 5000.000000000000 0.000000000000 -15911.617200000001 0.000000000000 -4543.503910000000 0.000000000000 0.000000000000 5000.000000000000 -2669.896000000000 4543.503910000000 0.000000000000 0.000000000000 -15911.617200000001 -2669.896000000000 53768.359400000001 -2088.679690000000 14498.599600000000 15911.617200000001 0.000000000000 4543.503910000000 -2088.679690000000 55363.324200000003 8762.063480000001 2669.896000000000 -4543.503910000000 0.000000000000 14498.599600000000 8762.063480000001 7350.620610000000 40 45 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10674.150400000000 -990.368591000000 0.000000000000 5000.000000000000 0.000000000000 -10674.150400000000 0.000000000000 -3912.757570000000 0.000000000000 0.000000000000 5000.000000000000 990.368591000000 3912.757570000000 0.000000000000 0.000000000000 -10674.150400000000 990.368591000000 23863.443400000000 600.597168000000 8465.404300000000 10674.150400000000 0.000000000000 3912.757570000000 600.597168000000 26334.744100000000 -1926.404910000000 -990.368591000000 -3912.757570000000 0.000000000000 8465.404300000000 -1926.404910000000 4351.348140000000 40 46 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10766.325199999999 -951.926270000000 0.000000000000 5000.000000000000 0.000000000000 -10766.325199999999 0.000000000000 -3774.025150000000 0.000000000000 0.000000000000 5000.000000000000 951.926270000000 3774.025150000000 0.000000000000 0.000000000000 -10766.325199999999 951.926270000000 24436.578099999999 535.732910000000 8228.264649999999 10766.325199999999 0.000000000000 3774.025150000000 535.732910000000 26509.425800000001 -1811.954590000000 -951.926270000000 -3774.025150000000 0.000000000000 8228.264649999999 -1811.954590000000 4289.676270000000 40 47 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10569.423800000000 -1493.137570000000 0.000000000000 5000.000000000000 0.000000000000 -10569.423800000000 0.000000000000 -3070.786620000000 0.000000000000 0.000000000000 5000.000000000000 1493.137570000000 3070.786620000000 0.000000000000 0.000000000000 -10569.423800000000 1493.137570000000 23368.761699999999 753.895935000000 6568.499020000000 10569.423800000000 0.000000000000 3070.786620000000 753.895935000000 24743.035199999998 -3015.871090000000 -1493.137570000000 -3070.786620000000 0.000000000000 6568.499020000000 -3015.871090000000 3145.611330000000 40 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10198.278300000000 -2727.052250000000 0.000000000000 5000.000000000000 0.000000000000 -10198.278300000000 0.000000000000 -3467.490720000000 0.000000000000 0.000000000000 5000.000000000000 2727.052250000000 3467.490720000000 0.000000000000 0.000000000000 -10198.278300000000 2727.052250000000 22502.988300000001 1881.688350000000 7097.117190000000 10198.278300000000 0.000000000000 3467.490720000000 1881.688350000000 23603.572300000000 -5552.814940000000 -2727.052250000000 -3467.490720000000 0.000000000000 7097.117190000000 -5552.814940000000 4312.253910000000 40 49 66 4884.000000000000 0.000000000000 0.000000000000 0.000000000000 10388.501000000000 -1317.981930000000 0.000000000000 4884.000000000000 0.000000000000 -10388.501000000000 0.000000000000 -4812.186520000000 0.000000000000 0.000000000000 4884.000000000000 1317.981930000000 4812.186520000000 0.000000000000 0.000000000000 -10388.501000000000 1317.981930000000 23136.990200000000 1149.712400000000 10323.866200000000 10388.501000000000 0.000000000000 4812.186520000000 1149.712400000000 27118.621100000000 -2628.573730000000 -1317.981930000000 -4812.186520000000 0.000000000000 10323.866200000000 -2628.573730000000 5772.854000000000 41 44 66 4801.000000000000 0.000000000000 0.000000000000 0.000000000000 9432.423830000000 -1243.857790000000 0.000000000000 4801.000000000000 0.000000000000 -9432.423830000000 0.000000000000 -4267.750490000000 0.000000000000 0.000000000000 4801.000000000000 1243.857790000000 4267.750490000000 0.000000000000 0.000000000000 -9432.423830000000 1243.857790000000 19528.363300000001 921.889282000000 8392.594730000001 9432.423830000000 0.000000000000 4267.750490000000 921.889282000000 22550.923800000000 -2483.418460000000 -1243.857790000000 -4267.750490000000 0.000000000000 8392.594730000001 -2483.418460000000 4868.058590000000 42 44 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9473.041020000001 -4731.036130000000 0.000000000000 5000.000000000000 0.000000000000 -9473.041020000001 0.000000000000 -5300.403810000000 0.000000000000 0.000000000000 5000.000000000000 4731.036130000000 5300.403810000000 0.000000000000 0.000000000000 -9473.041020000001 4731.036130000000 23764.259800000000 4715.293950000000 10115.380900000000 9473.041020000001 0.000000000000 5300.403810000000 4715.293950000000 24116.544900000001 -8656.769530000000 -4731.036130000000 -5300.403810000000 0.000000000000 10115.380900000000 -8656.769530000000 11625.551799999999 43 45 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10706.281300000001 -2948.620850000000 0.000000000000 5000.000000000000 0.000000000000 -10706.281300000001 0.000000000000 -5785.455080000000 0.000000000000 0.000000000000 5000.000000000000 2948.620850000000 5785.455080000000 0.000000000000 0.000000000000 -10706.281300000001 2948.620850000000 25818.378900000000 3385.667480000000 12397.270500000001 10706.281300000001 0.000000000000 5785.455080000000 3385.667480000000 30050.105500000001 -6084.817870000000 -2948.620850000000 -5785.455080000000 0.000000000000 12397.270500000001 -6084.817870000000 9624.688480000001 43 46 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10964.516600000001 -2989.362060000000 0.000000000000 5000.000000000000 0.000000000000 -10964.516600000001 0.000000000000 -5912.977540000000 0.000000000000 0.000000000000 5000.000000000000 2989.362060000000 5912.977540000000 0.000000000000 0.000000000000 -10964.516600000001 2989.362060000000 26699.855500000001 3415.329350000000 13000.942400000000 10964.516600000001 0.000000000000 5912.977540000000 3415.329350000000 31437.668000000001 -6352.215330000000 -2989.362060000000 -5912.977540000000 0.000000000000 13000.942400000000 -6352.215330000000 9676.833979999999 43 47 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11012.407200000000 -3226.178960000000 0.000000000000 5000.000000000000 0.000000000000 -11012.407200000000 0.000000000000 -5349.294920000000 0.000000000000 0.000000000000 5000.000000000000 3226.178960000000 5349.294920000000 0.000000000000 0.000000000000 -11012.407200000000 3226.178960000000 26794.140599999999 3402.372070000000 11788.822300000000 11012.407200000000 0.000000000000 5349.294920000000 3402.372070000000 30414.021499999999 -7018.552730000000 -3226.178960000000 -5349.294920000000 0.000000000000 11788.822300000000 -7018.552730000000 8396.135740000000 43 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10407.086900000000 -4211.703130000000 0.000000000000 5000.000000000000 0.000000000000 -10407.086900000000 0.000000000000 -5478.804690000000 0.000000000000 0.000000000000 5000.000000000000 4211.703130000000 5478.804690000000 0.000000000000 0.000000000000 -10407.086900000000 4211.703130000000 25475.339800000002 4620.640140000000 11417.834999999999 10407.086900000000 0.000000000000 5478.804690000000 4620.640140000000 28063.902300000002 -8740.728520000001 -4211.703130000000 -5478.804690000000 0.000000000000 11417.834999999999 -8740.728520000001 9931.518550000001 44 48 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12715.879900000000 -3268.079590000000 0.000000000000 5000.000000000000 0.000000000000 -12715.879900000000 0.000000000000 -1385.332760000000 0.000000000000 0.000000000000 5000.000000000000 3268.079590000000 1385.332760000000 0.000000000000 0.000000000000 -12715.879900000000 3268.079590000000 34983.976600000002 936.218445000000 3526.342530000000 12715.879900000000 0.000000000000 1385.332760000000 936.218445000000 34302.230499999998 -8300.694340000000 -3268.079590000000 -1385.332760000000 0.000000000000 3526.342530000000 -8300.694340000000 3890.427980000000 44 51 66 4814.000000000000 0.000000000000 0.000000000000 0.000000000000 15320.574199999999 153.669037000000 0.000000000000 4814.000000000000 0.000000000000 -15320.574199999999 0.000000000000 -4910.399900000000 0.000000000000 0.000000000000 4814.000000000000 -153.669037000000 4910.399900000000 0.000000000000 0.000000000000 -15320.574199999999 -153.669037000000 51282.820299999999 -167.885193000000 15484.006799999999 15320.574199999999 0.000000000000 4910.399900000000 -167.885193000000 54800.105499999998 979.649475000000 153.669037000000 -4910.399900000000 0.000000000000 15484.006799999999 979.649475000000 7004.218260000000 47 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13805.014600000000 2908.298580000000 0.000000000000 5000.000000000000 0.000000000000 -13805.014600000000 0.000000000000 -842.955750000000 0.000000000000 0.000000000000 5000.000000000000 -2908.298580000000 842.955750000000 0.000000000000 0.000000000000 -13805.014600000000 -2908.298580000000 41774.960899999998 -261.139923000000 1524.418090000000 13805.014600000000 0.000000000000 842.955750000000 -261.139923000000 40400.937500000000 8670.588870000000 2908.298580000000 -842.955750000000 0.000000000000 1524.418090000000 8670.588870000000 3449.256590000000 48 50 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13781.555700000001 4634.760250000000 0.000000000000 5000.000000000000 0.000000000000 -13781.555700000001 0.000000000000 -829.521423000000 0.000000000000 0.000000000000 5000.000000000000 -4634.760250000000 829.521423000000 0.000000000000 0.000000000000 -13781.555700000001 -4634.760250000000 43364.261700000003 -610.103333000000 1523.863040000000 13781.555700000001 0.000000000000 829.521423000000 -610.103333000000 39983.105499999998 12965.357400000001 4634.760250000000 -829.521423000000 0.000000000000 1523.863040000000 12965.357400000001 5624.305660000000 49 51 66 4073.000000000000 0.000000000000 0.000000000000 0.000000000000 10721.345700000000 3145.782230000000 0.000000000000 4073.000000000000 0.000000000000 -10721.345700000000 0.000000000000 -422.220917000000 0.000000000000 0.000000000000 4073.000000000000 -3145.782230000000 422.220917000000 0.000000000000 0.000000000000 -10721.345700000000 -3145.782230000000 32443.039100000002 160.921890000000 161.402084000000 10721.345700000000 0.000000000000 422.220917000000 160.921890000000 30336.083999999999 9005.487300000001 3145.782230000000 -422.220917000000 0.000000000000 161.402084000000 9005.487300000001 3718.638920000000 50 52 66 1852.000000000000 0.000000000000 0.000000000000 0.000000000000 5756.861330000000 -374.191467000000 0.000000000000 1852.000000000000 0.000000000000 -5756.861330000000 0.000000000000 -849.926331000000 0.000000000000 0.000000000000 1852.000000000000 374.191467000000 849.926331000000 0.000000000000 0.000000000000 -5756.861330000000 374.191467000000 19061.867200000001 482.109680000000 2533.260500000000 5756.861330000000 0.000000000000 849.926331000000 482.109680000000 20186.300800000001 -1070.696900000000 -374.191467000000 -849.926331000000 0.000000000000 2533.260500000000 -1070.696900000000 1887.057980000000 51 55 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15192.680700000001 -2033.420530000000 0.000000000000 5000.000000000000 0.000000000000 -15192.680700000001 0.000000000000 -5462.264160000000 0.000000000000 0.000000000000 5000.000000000000 2033.420530000000 5462.264160000000 0.000000000000 0.000000000000 -15192.680700000001 2033.420530000000 47799.875000000000 2138.415530000000 16501.666000000001 15192.680700000001 0.000000000000 5462.264160000000 2138.415530000000 52808.554700000001 -6111.407710000000 -2033.420530000000 -5462.264160000000 0.000000000000 16501.666000000001 -6111.407710000000 7689.281250000000 51 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14889.458000000001 -1883.463010000000 0.000000000000 5000.000000000000 0.000000000000 -14889.458000000001 0.000000000000 -6186.717290000000 0.000000000000 0.000000000000 5000.000000000000 1883.463010000000 6186.717290000000 0.000000000000 0.000000000000 -14889.458000000001 1883.463010000000 45918.492200000001 2292.245360000000 18397.552700000000 14889.458000000001 0.000000000000 6186.717290000000 2292.245360000000 52392.542999999998 -5519.647460000000 -1883.463010000000 -6186.717290000000 0.000000000000 18397.552700000000 -5519.647460000000 9051.670899999999 52 54 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15192.706099999999 516.481812000000 0.000000000000 5000.000000000000 0.000000000000 -15192.706099999999 0.000000000000 -3348.171880000000 0.000000000000 0.000000000000 5000.000000000000 -516.481812000000 3348.171880000000 0.000000000000 0.000000000000 -15192.706099999999 -516.481812000000 47542.750000000000 403.757324000000 9381.592769999999 15192.706099999999 0.000000000000 3348.171880000000 403.757324000000 51734.167999999998 1923.245120000000 516.481812000000 -3348.171880000000 0.000000000000 9381.592769999999 1923.245120000000 5603.097660000000 52 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13213.619100000000 -1655.148320000000 0.000000000000 5000.000000000000 0.000000000000 -13213.619100000000 0.000000000000 -5729.993650000000 0.000000000000 0.000000000000 5000.000000000000 1655.148320000000 5729.993650000000 0.000000000000 0.000000000000 -13213.619100000000 1655.148320000000 36534.160199999998 1743.233890000000 15237.879900000000 13213.619100000000 0.000000000000 5729.993650000000 1743.233890000000 42168.609400000001 -4218.775390000000 -1655.148320000000 -5729.993650000000 0.000000000000 15237.879900000000 -4218.775390000000 7876.707520000000 53 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11983.991200000000 -1415.101200000000 0.000000000000 5000.000000000000 0.000000000000 -11983.991200000000 0.000000000000 -5598.630370000000 0.000000000000 0.000000000000 5000.000000000000 1415.101200000000 5598.630370000000 0.000000000000 0.000000000000 -11983.991200000000 1415.101200000000 30285.605500000001 1387.221560000000 13615.593800000001 11983.991200000000 0.000000000000 5598.630370000000 1387.221560000000 36086.437500000000 -3289.545410000000 -1415.101200000000 -5598.630370000000 0.000000000000 13615.593800000001 -3289.545410000000 7309.227050000000 54 56 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11486.520500000001 -2788.890140000000 0.000000000000 5000.000000000000 0.000000000000 -11486.520500000001 0.000000000000 -5254.606450000000 0.000000000000 0.000000000000 5000.000000000000 2788.890140000000 5254.606450000000 0.000000000000 0.000000000000 -11486.520500000001 2788.890140000000 28953.978500000001 2898.306880000000 12287.663100000000 11486.520500000001 0.000000000000 5254.606450000000 2898.306880000000 33325.636700000003 -6328.634770000000 -2788.890140000000 -5254.606450000000 0.000000000000 12287.663100000000 -6328.634770000000 7546.301760000000 55 57 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9569.726559999999 -4240.994630000000 0.000000000000 5000.000000000000 0.000000000000 -9569.726559999999 0.000000000000 -5521.525880000000 0.000000000000 0.000000000000 5000.000000000000 4240.994630000000 5521.525880000000 0.000000000000 0.000000000000 -9569.726559999999 4240.994630000000 23087.519499999999 4692.974120000000 10830.213900000001 9569.726559999999 0.000000000000 5521.525880000000 4692.974120000000 25320.101600000002 -7869.755860000000 -4240.994630000000 -5521.525880000000 0.000000000000 10830.213900000001 -7869.755860000000 10627.953100000001 57 59 66 3862.000000000000 0.000000000000 0.000000000000 0.000000000000 11298.597700000000 -1053.704830000000 0.000000000000 3862.000000000000 0.000000000000 -11298.597700000000 0.000000000000 -5080.266110000000 0.000000000000 0.000000000000 3862.000000000000 1053.704830000000 5080.266110000000 0.000000000000 0.000000000000 -11298.597700000000 1053.704830000000 33914.667999999998 1383.060060000000 14841.872100000001 11298.597700000000 0.000000000000 5080.266110000000 1383.060060000000 40165.359400000001 -2876.080570000000 -1053.704830000000 -5080.266110000000 0.000000000000 14841.872100000001 -2876.080570000000 7246.064940000000 57 60 66 4245.000000000000 0.000000000000 0.000000000000 0.000000000000 11584.964800000000 -1636.921260000000 0.000000000000 4245.000000000000 0.000000000000 -11584.964800000000 0.000000000000 -5477.248540000000 0.000000000000 0.000000000000 4245.000000000000 1636.921260000000 5477.248540000000 0.000000000000 0.000000000000 -11584.964800000000 1636.921260000000 32871.652300000002 2093.193120000000 14988.467800000000 11584.964800000000 0.000000000000 5477.248540000000 2093.193120000000 39228.085899999998 -4237.703610000000 -1636.921260000000 -5477.248540000000 0.000000000000 14988.467800000000 -4237.703610000000 7889.227050000000 57 61 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12643.616200000000 -2282.451170000000 0.000000000000 5000.000000000000 0.000000000000 -12643.616200000000 0.000000000000 -5506.489750000000 0.000000000000 0.000000000000 5000.000000000000 2282.451170000000 5506.489750000000 0.000000000000 0.000000000000 -12643.616200000000 2282.451170000000 33918.781300000002 2423.662110000000 14130.314500000000 12643.616200000000 0.000000000000 5506.489750000000 2423.662110000000 38974.046900000001 -5484.082030000000 -2282.451170000000 -5506.489750000000 0.000000000000 14130.314500000000 -5484.082030000000 7477.160160000000 57 62 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12096.665000000001 -2457.061040000000 0.000000000000 5000.000000000000 0.000000000000 -12096.665000000001 0.000000000000 -4770.124020000000 0.000000000000 0.000000000000 5000.000000000000 2457.061040000000 4770.124020000000 0.000000000000 0.000000000000 -12096.665000000001 2457.061040000000 31208.408200000002 2227.962650000000 11836.410200000000 12096.665000000001 0.000000000000 4770.124020000000 2227.962650000000 34839.625000000000 -5778.679200000000 -2457.061040000000 -4770.124020000000 0.000000000000 11836.410200000000 -5778.679200000000 6241.067870000000 57 63 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11921.959999999999 -2538.718260000000 0.000000000000 5000.000000000000 0.000000000000 -11921.959999999999 0.000000000000 -5104.655760000000 0.000000000000 0.000000000000 5000.000000000000 2538.718260000000 5104.655760000000 0.000000000000 0.000000000000 -11921.959999999999 2538.718260000000 30356.798800000000 2467.006840000000 12511.660200000000 11921.959999999999 0.000000000000 5104.655760000000 2467.006840000000 34671.925799999997 -5916.354000000000 -2538.718260000000 -5104.655760000000 0.000000000000 12511.660200000000 -5916.354000000000 7066.909670000000 58 62 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11392.554700000001 -426.597626000000 0.000000000000 5000.000000000000 0.000000000000 -11392.554700000001 0.000000000000 -2941.511960000000 0.000000000000 0.000000000000 5000.000000000000 426.597626000000 2941.511960000000 0.000000000000 0.000000000000 -11392.554700000001 426.597626000000 27425.373000000000 -416.959717000000 6740.918460000000 11392.554700000001 0.000000000000 2941.511960000000 -416.959717000000 29063.078099999999 -833.019897000000 -426.597626000000 -2941.511960000000 0.000000000000 6740.918460000000 -833.019897000000 3885.137940000000 58 63 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10601.295899999999 -968.989685000000 0.000000000000 5000.000000000000 0.000000000000 -10601.295899999999 0.000000000000 -3786.288330000000 0.000000000000 0.000000000000 5000.000000000000 968.989685000000 3786.288330000000 0.000000000000 0.000000000000 -10601.295899999999 968.989685000000 24022.804700000001 78.764038100000 8100.453610000000 10601.295899999999 0.000000000000 3786.288330000000 78.764038100000 26512.277300000002 -2040.102540000000 -968.989685000000 -3786.288330000000 0.000000000000 8100.453610000000 -2040.102540000000 5111.190430000000 59 63 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9330.225590000000 -1855.240360000000 0.000000000000 5000.000000000000 0.000000000000 -9330.225590000000 0.000000000000 -2291.535160000000 0.000000000000 0.000000000000 5000.000000000000 1855.240360000000 2291.535160000000 0.000000000000 0.000000000000 -9330.225590000000 1855.240360000000 19075.500000000000 621.180359000000 4167.660640000000 9330.225590000000 0.000000000000 2291.535160000000 621.180359000000 19438.293000000001 -3510.325440000000 -1855.240360000000 -2291.535160000000 0.000000000000 4167.660640000000 -3510.325440000000 3027.372310000000 60 64 66 3573.000000000000 0.000000000000 0.000000000000 0.000000000000 5870.295410000000 -1225.976930000000 0.000000000000 3573.000000000000 0.000000000000 -5870.295410000000 0.000000000000 -3181.656010000000 0.000000000000 0.000000000000 3573.000000000000 1225.976930000000 3181.656010000000 0.000000000000 0.000000000000 -5870.295410000000 1225.976930000000 10734.996100000000 953.048035000000 5248.045900000000 5870.295410000000 0.000000000000 3181.656010000000 953.048035000000 12684.955099999999 -2035.729000000000 -1225.976930000000 -3181.656010000000 0.000000000000 5248.045900000000 -2035.729000000000 3847.364010000000 61 64 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9104.969730000001 -1085.468510000000 0.000000000000 5000.000000000000 0.000000000000 -9104.969730000001 0.000000000000 -5005.092290000000 0.000000000000 0.000000000000 5000.000000000000 1085.468510000000 5005.092290000000 0.000000000000 0.000000000000 -9104.969730000001 1085.468510000000 17882.050800000001 1198.556760000000 9072.204100000001 9104.969730000001 0.000000000000 5005.092290000000 1198.556760000000 22137.925800000001 -2138.219730000000 -1085.468510000000 -5005.092290000000 0.000000000000 9072.204100000001 -2138.219730000000 6017.569820000000 62 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14383.653300000000 2347.154540000000 0.000000000000 5000.000000000000 0.000000000000 -14383.653300000000 0.000000000000 -6335.245120000000 0.000000000000 0.000000000000 5000.000000000000 -2347.154540000000 6335.245120000000 0.000000000000 0.000000000000 -14383.653300000000 -2347.154540000000 43788.078099999999 -2865.274410000000 18123.201200000000 14383.653300000000 0.000000000000 6335.245120000000 -2865.274410000000 49917.089800000002 6995.491700000000 2347.154540000000 -6335.245120000000 0.000000000000 18123.201200000000 6995.491700000000 10192.910200000000 63 65 66 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15113.916999999999 2913.591550000000 0.000000000000 5000.000000000000 0.000000000000 -15113.916999999999 0.000000000000 -2320.384770000000 0.000000000000 0.000000000000 5000.000000000000 -2913.591550000000 2320.384770000000 0.000000000000 0.000000000000 -15113.916999999999 -2913.591550000000 48592.500000000000 -1083.515380000000 7046.188960000000 15113.916999999999 0.000000000000 2320.384770000000 -1083.515380000000 48211.707000000002 8768.540040000000 2913.591550000000 -2320.384770000000 0.000000000000 7046.188960000000 8768.540040000000 4443.391600000000 ================================================ FILE: benchmarks/3DLoMatch/sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika/gt.info ================================================ 0 2 38 1394.000000000000 0.000000000000 0.000000000000 0.000000000000 4493.447750000000 -1100.049070000000 0.000000000000 1394.000000000000 0.000000000000 -4493.447750000000 0.000000000000 -633.893188000000 0.000000000000 0.000000000000 1394.000000000000 1100.049070000000 633.893188000000 0.000000000000 0.000000000000 -4493.447750000000 1100.049070000000 15661.764600000000 346.228729000000 2046.095340000000 4493.447750000000 0.000000000000 633.893188000000 346.228729000000 15348.218800000001 -3543.658690000000 -1100.049070000000 -633.893188000000 0.000000000000 2046.095340000000 -3543.658690000000 1901.811160000000 0 6 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16203.415000000001 1246.970830000000 0.000000000000 5000.000000000000 0.000000000000 -16203.415000000001 0.000000000000 -6489.119140000000 0.000000000000 0.000000000000 5000.000000000000 -1246.970830000000 6489.119140000000 0.000000000000 0.000000000000 -16203.415000000001 -1246.970830000000 54053.375000000000 -1914.582280000000 21047.148399999998 16203.415000000001 0.000000000000 6489.119140000000 -1914.582280000000 61275.539100000002 4068.762450000000 1246.970830000000 -6489.119140000000 0.000000000000 21047.148399999998 4068.762450000000 10056.123000000000 0 7 38 2901.000000000000 0.000000000000 0.000000000000 0.000000000000 8233.022460000000 535.792236000000 0.000000000000 2901.000000000000 0.000000000000 -8233.022460000000 0.000000000000 -3059.754640000000 0.000000000000 0.000000000000 2901.000000000000 -535.792236000000 3059.754640000000 0.000000000000 0.000000000000 -8233.022460000000 -535.792236000000 25460.796900000001 -1532.382080000000 8591.042970000000 8233.022460000000 0.000000000000 3059.754640000000 -1532.382080000000 27407.771499999999 1474.622070000000 535.792236000000 -3059.754640000000 0.000000000000 8591.042970000000 1474.622070000000 5739.035640000000 0 11 38 3577.000000000000 0.000000000000 0.000000000000 0.000000000000 7039.385740000000 -2090.374760000000 0.000000000000 3577.000000000000 0.000000000000 -7039.385740000000 0.000000000000 -1287.988280000000 0.000000000000 0.000000000000 3577.000000000000 2090.374760000000 1287.988280000000 0.000000000000 0.000000000000 -7039.385740000000 2090.374760000000 16376.500000000000 975.797791000000 3444.951660000000 7039.385740000000 0.000000000000 1287.988280000000 975.797791000000 16753.470700000002 -4322.695800000000 -2090.374760000000 -1287.988280000000 0.000000000000 3444.951660000000 -4322.695800000000 3485.552980000000 0 24 38 1893.000000000000 0.000000000000 0.000000000000 0.000000000000 4520.606930000000 -1658.563720000000 0.000000000000 1893.000000000000 0.000000000000 -4520.606930000000 0.000000000000 500.010406000000 0.000000000000 0.000000000000 1893.000000000000 1658.563720000000 -500.010406000000 0.000000000000 0.000000000000 -4520.606930000000 1658.563720000000 13334.799800000001 -358.418365000000 -1065.013060000000 4520.606930000000 0.000000000000 -500.010406000000 -358.418365000000 11849.456099999999 -4379.745120000000 -1658.563720000000 500.010406000000 0.000000000000 -1065.013060000000 -4379.745120000000 1857.754150000000 0 26 38 2323.000000000000 0.000000000000 0.000000000000 0.000000000000 6497.819820000000 -2034.119510000000 0.000000000000 2323.000000000000 0.000000000000 -6497.819820000000 0.000000000000 731.670837000000 0.000000000000 0.000000000000 2323.000000000000 2034.119510000000 -731.670837000000 0.000000000000 0.000000000000 -6497.819820000000 2034.119510000000 21670.599600000001 -642.054382000000 -1871.684080000000 6497.819820000000 0.000000000000 -731.670837000000 -642.054382000000 20110.314500000000 -6217.002930000000 -2034.119510000000 731.670837000000 0.000000000000 -1871.684080000000 -6217.002930000000 2457.217290000000 1 5 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15848.346700000000 -138.255753000000 0.000000000000 5000.000000000000 0.000000000000 -15848.346700000000 0.000000000000 -4092.164550000000 0.000000000000 0.000000000000 5000.000000000000 138.255753000000 4092.164550000000 0.000000000000 0.000000000000 -15848.346700000000 138.255753000000 51158.007799999999 -333.700287000000 13051.244100000000 15848.346700000000 0.000000000000 4092.164550000000 -333.700287000000 54555.292999999998 -300.587646000000 -138.255753000000 -4092.164550000000 0.000000000000 13051.244100000000 -300.587646000000 5013.310060000000 1 7 38 3563.000000000000 0.000000000000 0.000000000000 0.000000000000 10114.388700000000 -640.843811000000 0.000000000000 3563.000000000000 0.000000000000 -10114.388700000000 0.000000000000 -1588.293210000000 0.000000000000 0.000000000000 3563.000000000000 640.843811000000 1588.293210000000 0.000000000000 0.000000000000 -10114.388700000000 640.843811000000 30404.375000000000 -392.589203000000 4213.363280000000 10114.388700000000 0.000000000000 1588.293210000000 -392.589203000000 30550.525399999999 -2043.069090000000 -640.843811000000 -1588.293210000000 0.000000000000 4213.363280000000 -2043.069090000000 2527.040770000000 1 26 38 3672.000000000000 0.000000000000 0.000000000000 0.000000000000 10084.204100000001 -3189.415280000000 0.000000000000 3672.000000000000 0.000000000000 -10084.204100000001 0.000000000000 2717.043460000000 0.000000000000 0.000000000000 3672.000000000000 3189.415280000000 -2717.043460000000 0.000000000000 0.000000000000 -10084.204100000001 3189.415280000000 30974.873000000000 -2481.239010000000 -7598.632320000000 10084.204100000001 0.000000000000 -2717.043460000000 -2481.239010000000 30717.640599999999 -8888.351559999999 -3189.415280000000 2717.043460000000 0.000000000000 -7598.632320000000 -8888.351559999999 5434.671390000000 2 6 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14198.469700000000 -408.202972000000 0.000000000000 5000.000000000000 0.000000000000 -14198.469700000000 0.000000000000 -2299.907960000000 0.000000000000 0.000000000000 5000.000000000000 408.202972000000 2299.907960000000 0.000000000000 0.000000000000 -14198.469700000000 408.202972000000 43224.281300000002 -168.752518000000 7027.820800000000 14198.469700000000 0.000000000000 2299.907960000000 -168.752518000000 43398.605499999998 -793.362549000000 -408.202972000000 -2299.907960000000 0.000000000000 7027.820800000000 -793.362549000000 3302.316890000000 2 7 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 14472.285200000000 -598.239685000000 0.000000000000 5000.000000000000 0.000000000000 -14472.285200000000 0.000000000000 -2439.142580000000 0.000000000000 0.000000000000 5000.000000000000 598.239685000000 2439.142580000000 0.000000000000 0.000000000000 -14472.285200000000 598.239685000000 44503.500000000000 42.886646300000 7802.671390000000 14472.285200000000 0.000000000000 2439.142580000000 42.886646300000 44864.968800000002 -1345.440800000000 -598.239685000000 -2439.142580000000 0.000000000000 7802.671390000000 -1345.440800000000 3185.039310000000 2 9 38 4047.000000000000 0.000000000000 0.000000000000 0.000000000000 8983.119140000001 -426.430542000000 0.000000000000 4047.000000000000 0.000000000000 -8983.119140000001 0.000000000000 -1996.913330000000 0.000000000000 0.000000000000 4047.000000000000 426.430542000000 1996.913330000000 0.000000000000 0.000000000000 -8983.119140000001 426.430542000000 21429.310500000000 -647.091797000000 4617.465330000000 8983.119140000001 0.000000000000 1996.913330000000 -647.091797000000 22256.490200000000 -785.892151000000 -426.430542000000 -1996.913330000000 0.000000000000 4617.465330000000 -785.892151000000 3346.439700000000 2 28 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12158.707000000000 -1691.472900000000 0.000000000000 5000.000000000000 0.000000000000 -12158.707000000000 0.000000000000 2277.264650000000 0.000000000000 0.000000000000 5000.000000000000 1691.472900000000 -2277.264650000000 0.000000000000 0.000000000000 -12158.707000000000 1691.472900000000 32381.562500000000 -458.725403000000 -6410.711910000000 12158.707000000000 0.000000000000 -2277.264650000000 -458.725403000000 33139.273399999998 -3470.722660000000 -1691.472900000000 2277.264650000000 0.000000000000 -6410.711910000000 -3470.722660000000 4945.553220000000 2 30 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16656.941400000000 834.740234000000 0.000000000000 5000.000000000000 0.000000000000 -16656.941400000000 0.000000000000 6474.793460000000 0.000000000000 0.000000000000 5000.000000000000 -834.740234000000 -6474.793460000000 0.000000000000 0.000000000000 -16656.941400000000 -834.740234000000 57228.562500000000 1072.235960000000 -21563.500000000000 16656.941400000000 0.000000000000 -6474.793460000000 1072.235960000000 63968.886700000003 2657.461670000000 834.740234000000 6474.793460000000 0.000000000000 -21563.500000000000 2657.461670000000 10159.589800000000 3 5 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12226.066400000000 -1080.383180000000 0.000000000000 5000.000000000000 0.000000000000 -12226.066400000000 0.000000000000 -1104.165770000000 0.000000000000 0.000000000000 5000.000000000000 1080.383180000000 1104.165770000000 0.000000000000 0.000000000000 -12226.066400000000 1080.383180000000 32943.410199999998 -350.510468000000 2729.469240000000 12226.066400000000 0.000000000000 1104.165770000000 -350.510468000000 31913.400399999999 -2599.438960000000 -1080.383180000000 -1104.165770000000 0.000000000000 2729.469240000000 -2599.438960000000 2606.579590000000 3 6 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11911.791999999999 -565.955017000000 0.000000000000 5000.000000000000 0.000000000000 -11911.791999999999 0.000000000000 -1739.606200000000 0.000000000000 0.000000000000 5000.000000000000 565.955017000000 1739.606200000000 0.000000000000 0.000000000000 -11911.791999999999 565.955017000000 31726.746100000000 -541.418091000000 4423.877930000000 11911.791999999999 0.000000000000 1739.606200000000 -541.418091000000 30871.878900000000 -1023.872680000000 -565.955017000000 -1739.606200000000 0.000000000000 4423.877930000000 -1023.872680000000 3189.879640000000 3 7 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12016.371100000000 1723.496460000000 0.000000000000 5000.000000000000 0.000000000000 -12016.371100000000 0.000000000000 -3087.242920000000 0.000000000000 0.000000000000 5000.000000000000 -1723.496460000000 3087.242920000000 0.000000000000 0.000000000000 -12016.371100000000 -1723.496460000000 31660.918000000001 -1437.549070000000 7862.676270000000 12016.371100000000 0.000000000000 3087.242920000000 -1437.549070000000 32258.197300000000 4934.513180000000 1723.496460000000 -3087.242920000000 0.000000000000 7862.676270000000 4934.513180000000 4125.825680000000 3 8 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9807.942380000000 523.966675000000 0.000000000000 5000.000000000000 0.000000000000 -9807.942380000000 0.000000000000 -2732.944580000000 0.000000000000 0.000000000000 5000.000000000000 -523.966675000000 2732.944580000000 0.000000000000 0.000000000000 -9807.942380000000 -523.966675000000 21785.468799999999 -883.010925000000 5998.812500000000 9807.942380000000 0.000000000000 2732.944580000000 -883.010925000000 22469.769499999999 2049.645510000000 523.966675000000 -2732.944580000000 0.000000000000 5998.812500000000 2049.645510000000 3390.308110000000 3 30 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12823.502899999999 443.884521000000 0.000000000000 5000.000000000000 0.000000000000 -12823.502899999999 0.000000000000 5859.620610000000 0.000000000000 0.000000000000 5000.000000000000 -443.884521000000 -5859.620610000000 0.000000000000 0.000000000000 -12823.502899999999 -443.884521000000 34053.203099999999 516.939758000000 -15025.046899999999 12823.502899999999 0.000000000000 -5859.620610000000 516.939758000000 39847.863299999997 1033.419560000000 443.884521000000 5859.620610000000 0.000000000000 -15025.046899999999 1033.419560000000 8056.273440000000 4 7 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10763.953100000001 49.599918400000 0.000000000000 5000.000000000000 0.000000000000 -10763.953100000001 0.000000000000 -3664.630130000000 0.000000000000 0.000000000000 5000.000000000000 -49.599918400000 3664.630130000000 0.000000000000 0.000000000000 -10763.953100000001 -49.599918400000 25362.490200000000 -223.195053000000 8109.821780000000 10763.953100000001 0.000000000000 3664.630130000000 -223.195053000000 26863.242200000001 65.468025200000 49.599918400000 -3664.630130000000 0.000000000000 8109.821780000000 65.468025200000 4451.818850000000 4 8 38 3834.000000000000 0.000000000000 0.000000000000 0.000000000000 6288.564940000000 160.468185000000 0.000000000000 3834.000000000000 0.000000000000 -6288.564940000000 0.000000000000 -2656.670170000000 0.000000000000 0.000000000000 3834.000000000000 -160.468185000000 2656.670170000000 0.000000000000 0.000000000000 -6288.564940000000 -160.468185000000 12113.253900000000 -472.622162000000 4805.711430000000 6288.564940000000 0.000000000000 2656.670170000000 -472.622162000000 13477.064500000000 729.800415000000 160.468185000000 -2656.670170000000 0.000000000000 4805.711430000000 729.800415000000 3036.985600000000 5 9 38 4350.000000000000 0.000000000000 0.000000000000 0.000000000000 6474.356930000000 878.969299000000 0.000000000000 4350.000000000000 0.000000000000 -6474.356930000000 0.000000000000 -5610.881350000000 0.000000000000 0.000000000000 4350.000000000000 -878.969299000000 5610.881350000000 0.000000000000 0.000000000000 -6474.356930000000 -878.969299000000 10640.401400000001 -1361.818480000000 8533.590819999999 6474.356930000000 0.000000000000 5610.881350000000 -1361.818480000000 17364.333999999999 1472.484990000000 878.969299000000 -5610.881350000000 0.000000000000 8533.590819999999 1472.484990000000 8418.644530000000 6 9 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10519.634800000000 1851.038570000000 0.000000000000 5000.000000000000 0.000000000000 -10519.634800000000 0.000000000000 -5707.545410000000 0.000000000000 0.000000000000 5000.000000000000 -1851.038570000000 5707.545410000000 0.000000000000 0.000000000000 -10519.634800000000 -1851.038570000000 24655.910199999998 -2266.351070000000 12146.370100000000 10519.634800000000 0.000000000000 5707.545410000000 -2266.351070000000 29197.138700000000 3982.375000000000 1851.038570000000 -5707.545410000000 0.000000000000 12146.370100000000 3982.375000000000 9107.483399999999 6 10 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9977.884770000001 2080.491460000000 0.000000000000 5000.000000000000 0.000000000000 -9977.884770000001 0.000000000000 -6790.816410000000 0.000000000000 0.000000000000 5000.000000000000 -2080.491460000000 6790.816410000000 0.000000000000 0.000000000000 -9977.884770000001 -2080.491460000000 23389.767599999999 -2859.617920000000 13598.962900000000 9977.884770000001 0.000000000000 6790.816410000000 -2859.617920000000 29439.892599999999 4172.968750000000 2080.491460000000 -6790.816410000000 0.000000000000 13598.962900000000 4172.968750000000 12574.485400000000 8 9 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13339.186500000000 -2608.160890000000 0.000000000000 5000.000000000000 0.000000000000 -13339.186500000000 0.000000000000 -1961.195920000000 0.000000000000 0.000000000000 5000.000000000000 2608.160890000000 1961.195920000000 0.000000000000 0.000000000000 -13339.186500000000 2608.160890000000 41107.203099999999 2344.828860000000 4880.921390000000 13339.186500000000 0.000000000000 1961.195920000000 2344.828860000000 38944.203099999999 -5644.387700000000 -2608.160890000000 -1961.195920000000 0.000000000000 4880.921390000000 -5644.387700000000 6846.211430000000 8 10 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 13156.114299999999 -3030.622560000000 0.000000000000 5000.000000000000 0.000000000000 -13156.114299999999 0.000000000000 -3519.425780000000 0.000000000000 0.000000000000 5000.000000000000 3030.622560000000 3519.425780000000 0.000000000000 0.000000000000 -13156.114299999999 3030.622560000000 40642.074200000003 3302.877200000000 8975.156250000000 13156.114299999999 0.000000000000 3519.425780000000 3302.877200000000 39187.667999999998 -6564.583500000000 -3030.622560000000 -3519.425780000000 0.000000000000 8975.156250000000 -6564.583500000000 8675.739260000000 9 11 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15661.225600000000 -4748.933110000000 0.000000000000 5000.000000000000 0.000000000000 -15661.225600000000 0.000000000000 -3775.423100000000 0.000000000000 0.000000000000 5000.000000000000 4748.933110000000 3775.423100000000 0.000000000000 0.000000000000 -15661.225600000000 4748.933110000000 54389.183599999997 3779.331050000000 11694.340800000000 15661.225600000000 0.000000000000 3775.423100000000 3779.331050000000 53446.644500000002 -14997.071300000000 -4748.933110000000 -3775.423100000000 0.000000000000 11694.340800000000 -14997.071300000000 8554.274410000000 9 27 38 3742.000000000000 0.000000000000 0.000000000000 0.000000000000 10090.821300000000 -2451.779790000000 0.000000000000 3742.000000000000 0.000000000000 -10090.821300000000 0.000000000000 1721.609620000000 0.000000000000 0.000000000000 3742.000000000000 2451.779790000000 -1721.609620000000 0.000000000000 0.000000000000 -10090.821300000000 2451.779790000000 30141.306600000000 -920.500061000000 -4972.411620000000 10090.821300000000 0.000000000000 -1721.609620000000 -920.500061000000 29581.285199999998 -6252.286130000000 -2451.779790000000 1721.609620000000 0.000000000000 -4972.411620000000 -6252.286130000000 4381.035160000000 9 28 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12317.194299999999 -3330.153560000000 0.000000000000 5000.000000000000 0.000000000000 -12317.194299999999 0.000000000000 4262.634280000000 0.000000000000 0.000000000000 5000.000000000000 3330.153560000000 -4262.634280000000 0.000000000000 0.000000000000 -12317.194299999999 3330.153560000000 33126.980499999998 -2617.314700000000 -10447.523400000000 12317.194299999999 0.000000000000 -4262.634280000000 -2617.314700000000 34480.207000000002 -8254.349609999999 -3330.153560000000 4262.634280000000 0.000000000000 -10447.523400000000 -8254.349609999999 6615.992190000000 10 27 38 4542.000000000000 0.000000000000 0.000000000000 0.000000000000 12611.951200000000 -2309.384770000000 0.000000000000 4542.000000000000 0.000000000000 -12611.951200000000 0.000000000000 2953.365480000000 0.000000000000 0.000000000000 4542.000000000000 2309.384770000000 -2953.365480000000 0.000000000000 0.000000000000 -12611.951200000000 2309.384770000000 38191.585899999998 -447.476929000000 -8863.658200000000 12611.951200000000 0.000000000000 -2953.365480000000 -447.476929000000 39386.972699999998 -5735.217770000000 -2309.384770000000 2953.365480000000 0.000000000000 -8863.658200000000 -5735.217770000000 6488.576660000000 10 28 38 4610.000000000000 0.000000000000 0.000000000000 0.000000000000 11458.188500000000 -3704.733400000000 0.000000000000 4610.000000000000 0.000000000000 -11458.188500000000 0.000000000000 3360.276120000000 0.000000000000 0.000000000000 4610.000000000000 3704.733400000000 -3360.276120000000 0.000000000000 0.000000000000 -11458.188500000000 3704.733400000000 31792.113300000001 -2608.484130000000 -8301.693359999999 11458.188500000000 0.000000000000 -3360.276120000000 -2608.484130000000 31336.502000000000 -9244.344730000001 -3704.733400000000 3360.276120000000 0.000000000000 -8301.693359999999 -9244.344730000001 5863.141110000000 13 16 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16261.694299999999 -2298.387210000000 0.000000000000 5000.000000000000 0.000000000000 -16261.694299999999 0.000000000000 -5140.891600000000 0.000000000000 0.000000000000 5000.000000000000 2298.387210000000 5140.891600000000 0.000000000000 0.000000000000 -16261.694299999999 2298.387210000000 56337.503900000003 1777.335210000000 16953.341799999998 16261.694299999999 0.000000000000 5140.891600000000 1777.335210000000 59435.390599999999 -7289.948730000000 -2298.387210000000 -5140.891600000000 0.000000000000 16953.341799999998 -7289.948730000000 9271.009770000001 13 17 38 4579.000000000000 0.000000000000 0.000000000000 0.000000000000 15320.571300000000 912.522644000000 0.000000000000 4579.000000000000 0.000000000000 -15320.571300000000 0.000000000000 -5678.572750000000 0.000000000000 0.000000000000 4579.000000000000 -912.522644000000 5678.572750000000 0.000000000000 0.000000000000 -15320.571300000000 -912.522644000000 52676.375000000000 -797.956238000000 18954.455099999999 15320.571300000000 0.000000000000 5678.572750000000 -797.956238000000 58643.800799999997 3050.085690000000 912.522644000000 -5678.572750000000 0.000000000000 18954.455099999999 3050.085690000000 8778.420899999999 13 18 38 2925.000000000000 0.000000000000 0.000000000000 0.000000000000 9755.024410000000 311.017731000000 0.000000000000 2925.000000000000 0.000000000000 -9755.024410000000 0.000000000000 -3972.643310000000 0.000000000000 0.000000000000 2925.000000000000 -311.017731000000 3972.643310000000 0.000000000000 0.000000000000 -9755.024410000000 -311.017731000000 32900.472699999998 -369.338043000000 13244.131799999999 9755.024410000000 0.000000000000 3972.643310000000 -369.338043000000 37966.757799999999 1029.369630000000 311.017731000000 -3972.643310000000 0.000000000000 13244.131799999999 1029.369630000000 5797.082030000000 14 18 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16017.529300000000 -1642.555660000000 0.000000000000 5000.000000000000 0.000000000000 -16017.529300000000 0.000000000000 -3817.166990000000 0.000000000000 0.000000000000 5000.000000000000 1642.555660000000 3817.166990000000 0.000000000000 0.000000000000 -16017.529300000000 1642.555660000000 53792.152300000002 1725.408570000000 12577.017599999999 16017.529300000000 0.000000000000 3817.166990000000 1725.408570000000 55868.785199999998 -5351.593750000000 -1642.555660000000 -3817.166990000000 0.000000000000 12577.017599999999 -5351.593750000000 6678.087400000000 15 18 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15637.957000000000 -840.665649000000 0.000000000000 5000.000000000000 0.000000000000 -15637.957000000000 0.000000000000 -3365.674070000000 0.000000000000 0.000000000000 5000.000000000000 840.665649000000 3365.674070000000 0.000000000000 0.000000000000 -15637.957000000000 840.665649000000 51310.035199999998 1141.595090000000 10981.359399999999 15637.957000000000 0.000000000000 3365.674070000000 1141.595090000000 52817.445299999999 -2841.567870000000 -840.665649000000 -3365.674070000000 0.000000000000 10981.359399999999 -2841.567870000000 5834.463380000000 17 20 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 15650.666999999999 -1919.970210000000 0.000000000000 5000.000000000000 0.000000000000 -15650.666999999999 0.000000000000 -6437.197750000000 0.000000000000 0.000000000000 5000.000000000000 1919.970210000000 6437.197750000000 0.000000000000 0.000000000000 -15650.666999999999 1919.970210000000 51735.933599999997 2467.603520000000 20170.375000000000 15650.666999999999 0.000000000000 6437.197750000000 2467.603520000000 57669.792999999998 -5730.384770000000 -1919.970210000000 -6437.197750000000 0.000000000000 20170.375000000000 -5730.384770000000 10914.735400000000 19 21 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12292.787100000000 -865.219482000000 0.000000000000 5000.000000000000 0.000000000000 -12292.787100000000 0.000000000000 -5581.024410000000 0.000000000000 0.000000000000 5000.000000000000 865.219482000000 5581.024410000000 0.000000000000 0.000000000000 -12292.787100000000 865.219482000000 32853.742200000001 847.713623000000 13720.893599999999 12292.787100000000 0.000000000000 5581.024410000000 847.713623000000 36922.695299999999 -2002.483400000000 -865.219482000000 -5581.024410000000 0.000000000000 13720.893599999999 -2002.483400000000 9109.723630000000 20 22 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12482.116200000000 119.604431000000 0.000000000000 5000.000000000000 0.000000000000 -12482.116200000000 0.000000000000 -5939.356930000000 0.000000000000 0.000000000000 5000.000000000000 -119.604431000000 5939.356930000000 0.000000000000 0.000000000000 -12482.116200000000 -119.604431000000 34747.492200000001 -288.661407000000 14874.192400000000 12482.116200000000 0.000000000000 5939.356930000000 -288.661407000000 39186.179700000001 1365.788820000000 119.604431000000 -5939.356930000000 0.000000000000 14874.192400000000 1365.788820000000 10256.801799999999 21 23 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12316.097700000000 -2588.687500000000 0.000000000000 5000.000000000000 0.000000000000 -12316.097700000000 0.000000000000 -4077.618650000000 0.000000000000 0.000000000000 5000.000000000000 2588.687500000000 4077.618650000000 0.000000000000 0.000000000000 -12316.097700000000 2588.687500000000 35337.832000000002 2784.286130000000 9459.695309999999 12316.097700000000 0.000000000000 4077.618650000000 2784.286130000000 36774.785199999998 -5485.178710000000 -2588.687500000000 -4077.618650000000 0.000000000000 9459.695309999999 -5485.178710000000 7170.731930000000 21 24 38 4846.000000000000 0.000000000000 0.000000000000 0.000000000000 9773.312500000000 -3584.125000000000 0.000000000000 4846.000000000000 0.000000000000 -9773.312500000000 0.000000000000 -5067.264160000000 0.000000000000 0.000000000000 4846.000000000000 3584.125000000000 5067.264160000000 0.000000000000 0.000000000000 -9773.312500000000 3584.125000000000 23749.287100000001 3778.279300000000 10458.379900000000 9773.312500000000 0.000000000000 5067.264160000000 3778.279300000000 26370.232400000001 -7680.589360000000 -3584.125000000000 -5067.264160000000 0.000000000000 10458.379900000000 -7680.589360000000 8646.548830000000 21 25 38 3557.000000000000 0.000000000000 0.000000000000 0.000000000000 6888.473140000000 -2348.145020000000 0.000000000000 3557.000000000000 0.000000000000 -6888.473140000000 0.000000000000 -3962.788820000000 0.000000000000 0.000000000000 3557.000000000000 2348.145020000000 3962.788820000000 0.000000000000 0.000000000000 -6888.473140000000 2348.145020000000 15927.239299999999 2721.846440000000 7860.575200000000 6888.473140000000 0.000000000000 3962.788820000000 2721.846440000000 18616.787100000001 -4950.855960000000 -2348.145020000000 -3962.788820000000 0.000000000000 7860.575200000000 -4950.855960000000 6436.289060000000 22 25 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 12387.689500000000 -3181.543950000000 0.000000000000 5000.000000000000 0.000000000000 -12387.689500000000 0.000000000000 -2769.260740000000 0.000000000000 0.000000000000 5000.000000000000 3181.543950000000 2769.260740000000 0.000000000000 0.000000000000 -12387.689500000000 3181.543950000000 34387.023399999998 1829.394780000000 6580.939940000000 12387.689500000000 0.000000000000 2769.260740000000 1829.394780000000 34678.179700000001 -8204.147460000000 -3181.543950000000 -2769.260740000000 0.000000000000 6580.939940000000 -8204.147460000000 4957.119140000000 22 26 38 4633.000000000000 0.000000000000 0.000000000000 0.000000000000 10153.206099999999 -2846.917720000000 0.000000000000 4633.000000000000 0.000000000000 -10153.206099999999 0.000000000000 -4425.875980000000 0.000000000000 0.000000000000 4633.000000000000 2846.917720000000 4425.875980000000 0.000000000000 0.000000000000 -10153.206099999999 2846.917720000000 25009.519499999999 3060.529300000000 10013.876000000000 10153.206099999999 0.000000000000 4425.875980000000 3060.529300000000 27578.306600000000 -6490.675290000000 -2846.917720000000 -4425.875980000000 0.000000000000 10013.876000000000 -6490.675290000000 6911.590330000000 23 26 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11787.607400000001 -1633.015500000000 0.000000000000 5000.000000000000 0.000000000000 -11787.607400000001 0.000000000000 -4393.832030000000 0.000000000000 0.000000000000 5000.000000000000 1633.015500000000 4393.832030000000 0.000000000000 0.000000000000 -11787.607400000001 1633.015500000000 29352.064500000000 1796.381710000000 10859.416999999999 11787.607400000001 0.000000000000 4393.832030000000 1796.381710000000 33115.898399999998 -4083.413570000000 -1633.015500000000 -4393.832030000000 0.000000000000 10859.416999999999 -4083.413570000000 5517.269530000000 23 27 38 3476.000000000000 0.000000000000 0.000000000000 0.000000000000 8279.242190000001 -999.641174000000 0.000000000000 3476.000000000000 0.000000000000 -8279.242190000001 0.000000000000 -3279.321780000000 0.000000000000 0.000000000000 3476.000000000000 999.641174000000 3279.321780000000 0.000000000000 0.000000000000 -8279.242190000001 999.641174000000 20663.699199999999 1260.589970000000 8144.740230000000 8279.242190000001 0.000000000000 3279.321780000000 1260.589970000000 23718.191400000000 -2602.135500000000 -999.641174000000 -3279.321780000000 0.000000000000 8144.740230000000 -2602.135500000000 4183.286620000000 24 26 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10613.726600000000 -1854.396360000000 0.000000000000 5000.000000000000 0.000000000000 -10613.726600000000 0.000000000000 -3568.036130000000 0.000000000000 0.000000000000 5000.000000000000 1854.396360000000 3568.036130000000 0.000000000000 0.000000000000 -10613.726600000000 1854.396360000000 24521.331999999999 1628.604130000000 8134.913570000000 10613.726600000000 0.000000000000 3568.036130000000 1628.604130000000 26780.955099999999 -4142.900390000000 -1854.396360000000 -3568.036130000000 0.000000000000 8134.913570000000 -4142.900390000000 4307.191410000000 24 27 38 4896.000000000000 0.000000000000 0.000000000000 0.000000000000 11369.461900000000 -1832.993530000000 0.000000000000 4896.000000000000 0.000000000000 -11369.461900000000 0.000000000000 -4666.218260000000 0.000000000000 0.000000000000 4896.000000000000 1832.993530000000 4666.218260000000 0.000000000000 0.000000000000 -11369.461900000000 1832.993530000000 28242.830099999999 2078.230470000000 11572.012699999999 11369.461900000000 0.000000000000 4666.218260000000 2078.230470000000 32582.636699999999 -4524.834960000000 -1832.993530000000 -4666.218260000000 0.000000000000 11572.012699999999 -4524.834960000000 6246.847660000000 24 33 38 4992.000000000000 0.000000000000 0.000000000000 0.000000000000 16562.293000000001 2896.648680000000 0.000000000000 4992.000000000000 0.000000000000 -16562.293000000001 0.000000000000 6304.151370000000 0.000000000000 0.000000000000 4992.000000000000 -2896.648680000000 -6304.151370000000 0.000000000000 0.000000000000 -16562.293000000001 -2896.648680000000 57420.671900000001 3465.439450000000 -20870.736300000000 16562.293000000001 0.000000000000 -6304.151370000000 3465.439450000000 63051.843800000002 9644.303710000000 2896.648680000000 6304.151370000000 0.000000000000 -20870.736300000000 9644.303710000000 10453.051799999999 24 34 38 2773.000000000000 0.000000000000 0.000000000000 0.000000000000 9315.701170000000 1607.216550000000 0.000000000000 2773.000000000000 0.000000000000 -9315.701170000000 0.000000000000 3418.798100000000 0.000000000000 0.000000000000 2773.000000000000 -1607.216550000000 -3418.798100000000 0.000000000000 0.000000000000 -9315.701170000000 -1607.216550000000 32526.687500000000 1902.793820000000 -11463.143599999999 9315.701170000000 0.000000000000 -3418.798100000000 1902.793820000000 35581.437500000000 5408.478030000000 1607.216550000000 3418.798100000000 0.000000000000 -11463.143599999999 5408.478030000000 5452.987300000000 24 35 38 3370.000000000000 0.000000000000 0.000000000000 0.000000000000 11222.008800000000 2408.365480000000 0.000000000000 3370.000000000000 0.000000000000 -11222.008800000000 0.000000000000 4109.623540000000 0.000000000000 0.000000000000 3370.000000000000 -2408.365480000000 -4109.623540000000 0.000000000000 0.000000000000 -11222.008800000000 -2408.365480000000 39329.546900000001 2872.888670000000 -13646.406300000001 11222.008800000000 0.000000000000 -4109.623540000000 2872.888670000000 42479.503900000003 8036.249020000000 2408.365480000000 4109.623540000000 0.000000000000 -13646.406300000001 8036.249020000000 6971.778320000000 24 36 38 2020.000000000000 0.000000000000 0.000000000000 0.000000000000 6827.119140000000 1731.794800000000 0.000000000000 2020.000000000000 0.000000000000 -6827.119140000000 0.000000000000 2330.365480000000 0.000000000000 0.000000000000 2020.000000000000 -1731.794800000000 -2330.365480000000 0.000000000000 0.000000000000 -6827.119140000000 -1731.794800000000 24686.931600000000 1977.846680000000 -7864.891110000000 6827.119140000000 0.000000000000 -2330.365480000000 1977.846680000000 25799.822300000000 5837.072750000000 1731.794800000000 2330.365480000000 0.000000000000 -7864.891110000000 5837.072750000000 4305.723630000000 24 37 38 2902.000000000000 0.000000000000 0.000000000000 0.000000000000 9689.880859999999 2257.202390000000 0.000000000000 2902.000000000000 0.000000000000 -9689.880859999999 0.000000000000 3497.087400000000 0.000000000000 0.000000000000 2902.000000000000 -2257.202390000000 -3497.087400000000 0.000000000000 0.000000000000 -9689.880859999999 -2257.202390000000 34366.496099999997 2654.170900000000 -11646.556600000000 9689.880859999999 0.000000000000 -3497.087400000000 2654.170900000000 36654.027300000002 7541.774900000000 2257.202390000000 3497.087400000000 0.000000000000 -11646.556600000000 7541.774900000000 6230.415530000000 25 27 38 3109.000000000000 0.000000000000 0.000000000000 0.000000000000 6309.675780000000 -1161.396730000000 0.000000000000 3109.000000000000 0.000000000000 -6309.675780000000 0.000000000000 -2438.135010000000 0.000000000000 0.000000000000 3109.000000000000 1161.396730000000 2438.135010000000 0.000000000000 0.000000000000 -6309.675780000000 1161.396730000000 14042.145500000001 1100.832030000000 5251.087400000000 6309.675780000000 0.000000000000 2438.135010000000 1100.832030000000 15632.400400000000 -2600.563960000000 -1161.396730000000 -2438.135010000000 0.000000000000 5251.087400000000 -2600.563960000000 2866.302490000000 25 30 38 2282.000000000000 0.000000000000 0.000000000000 0.000000000000 7606.167970000000 2163.755620000000 0.000000000000 2282.000000000000 0.000000000000 -7606.167970000000 0.000000000000 2563.639890000000 0.000000000000 0.000000000000 2282.000000000000 -2163.755620000000 -2563.639890000000 0.000000000000 0.000000000000 -7606.167970000000 -2163.755620000000 27623.412100000001 2417.449950000000 -8540.096680000001 7606.167970000000 0.000000000000 -2563.639890000000 2417.449950000000 28263.199199999999 7193.472660000000 2163.755620000000 2563.639890000000 0.000000000000 -8540.096680000001 7193.472660000000 5125.118650000000 25 31 38 1741.000000000000 0.000000000000 0.000000000000 0.000000000000 5784.838380000000 1761.141970000000 0.000000000000 1741.000000000000 0.000000000000 -5784.838380000000 0.000000000000 1962.899410000000 0.000000000000 0.000000000000 1741.000000000000 -1761.141970000000 -1962.899410000000 0.000000000000 0.000000000000 -5784.838380000000 -1761.141970000000 21116.724600000001 1979.116210000000 -6517.830570000000 5784.838380000000 0.000000000000 -1962.899410000000 1979.116210000000 21458.628900000000 5841.034670000000 1761.141970000000 1962.899410000000 0.000000000000 -6517.830570000000 5841.034670000000 4087.802250000000 25 32 38 3198.000000000000 0.000000000000 0.000000000000 0.000000000000 10364.594700000000 2991.134030000000 0.000000000000 3198.000000000000 0.000000000000 -10364.594700000000 0.000000000000 3700.421880000000 0.000000000000 0.000000000000 3198.000000000000 -2991.134030000000 -3700.421880000000 0.000000000000 0.000000000000 -10364.594700000000 -2991.134030000000 36868.550799999997 3432.068120000000 -11964.089800000000 10364.594700000000 0.000000000000 -3700.421880000000 3432.068120000000 38005.507799999999 9641.084960000000 2991.134030000000 3700.421880000000 0.000000000000 -11964.089800000000 9641.084960000000 7452.209470000000 25 33 38 3851.000000000000 0.000000000000 0.000000000000 0.000000000000 12491.593800000001 2987.415770000000 0.000000000000 3851.000000000000 0.000000000000 -12491.593800000001 0.000000000000 4515.544430000000 0.000000000000 0.000000000000 3851.000000000000 -2987.415770000000 -4515.544430000000 0.000000000000 0.000000000000 -12491.593800000001 -2987.415770000000 43833.320299999999 3416.495360000000 -14609.675800000001 12491.593800000001 0.000000000000 -4515.544430000000 3416.495360000000 45967.902300000002 9673.046880000000 2987.415770000000 4515.544430000000 0.000000000000 -14609.675800000001 9673.046880000000 8510.581050000001 25 34 38 4198.000000000000 0.000000000000 0.000000000000 0.000000000000 13443.137699999999 2603.708740000000 0.000000000000 4198.000000000000 0.000000000000 -13443.137699999999 0.000000000000 5072.259280000000 0.000000000000 0.000000000000 4198.000000000000 -2603.708740000000 -5072.259280000000 0.000000000000 0.000000000000 -13443.137699999999 -2603.708740000000 45592.378900000003 3032.225340000000 -16168.453100000001 13443.137699999999 0.000000000000 -5072.259280000000 3032.225340000000 49401.246099999997 8392.897460000000 2603.708740000000 5072.259280000000 0.000000000000 -16168.453100000001 8392.897460000000 8544.277340000001 25 35 38 2824.000000000000 0.000000000000 0.000000000000 0.000000000000 9034.178710000000 2321.629880000000 0.000000000000 2824.000000000000 0.000000000000 -9034.178710000000 0.000000000000 3331.918700000000 0.000000000000 0.000000000000 2824.000000000000 -2321.629880000000 -3331.918700000000 0.000000000000 0.000000000000 -9034.178710000000 -2321.629880000000 31153.269499999999 2701.147710000000 -10618.234399999999 9034.178710000000 0.000000000000 -3331.918700000000 2701.147710000000 32965.378900000003 7455.757810000000 2321.629880000000 3331.918700000000 0.000000000000 -10618.234399999999 7455.757810000000 6090.914060000000 25 36 38 3349.000000000000 0.000000000000 0.000000000000 0.000000000000 10884.334000000001 2568.810300000000 0.000000000000 3349.000000000000 0.000000000000 -10884.334000000001 0.000000000000 3917.579350000000 0.000000000000 0.000000000000 3349.000000000000 -2568.810300000000 -3917.579350000000 0.000000000000 0.000000000000 -10884.334000000001 -2568.810300000000 38038.054700000001 2953.237060000000 -12705.833000000001 10884.334000000001 0.000000000000 -3917.579350000000 2953.237060000000 40091.171900000001 8272.656250000000 2568.810300000000 3917.579350000000 0.000000000000 -12705.833000000001 8272.656250000000 7145.816410000000 25 37 38 3308.000000000000 0.000000000000 0.000000000000 0.000000000000 10662.143599999999 2744.333980000000 0.000000000000 3308.000000000000 0.000000000000 -10662.143599999999 0.000000000000 3893.786870000000 0.000000000000 0.000000000000 3308.000000000000 -2744.333980000000 -3893.786870000000 0.000000000000 0.000000000000 -10662.143599999999 -2744.333980000000 37327.429700000001 3167.116700000000 -12512.924800000001 10662.143599999999 0.000000000000 -3893.786870000000 3167.116700000000 39101.503900000003 8813.709960000000 2744.333980000000 3893.786870000000 0.000000000000 -12512.924800000001 8813.709960000000 7439.042970000000 28 29 38 3264.000000000000 0.000000000000 0.000000000000 0.000000000000 10624.295899999999 -1438.229740000000 0.000000000000 3264.000000000000 0.000000000000 -10624.295899999999 0.000000000000 1398.366580000000 0.000000000000 0.000000000000 3264.000000000000 1438.229740000000 -1398.366580000000 0.000000000000 0.000000000000 -10624.295899999999 1438.229740000000 35320.656300000002 -629.590332000000 -4522.155270000000 10624.295899999999 0.000000000000 -1398.366580000000 -629.590332000000 35500.070299999999 -4669.771480000000 -1438.229740000000 1398.366580000000 0.000000000000 -4522.155270000000 -4669.771480000000 1460.459720000000 28 30 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16985.808600000000 3552.437010000000 0.000000000000 5000.000000000000 0.000000000000 -16985.808600000000 0.000000000000 4628.713870000000 0.000000000000 0.000000000000 5000.000000000000 -3552.437010000000 -4628.713870000000 0.000000000000 0.000000000000 -16985.808600000000 -3552.437010000000 62367.316400000003 3704.693600000000 -15742.607400000001 16985.808600000000 0.000000000000 -4628.713870000000 3704.693600000000 62185.671900000001 12102.903300000000 3552.437010000000 4628.713870000000 0.000000000000 -15742.607400000001 12102.903300000000 9088.843750000000 29 31 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 16161.228499999999 -1411.428220000000 0.000000000000 5000.000000000000 0.000000000000 -16161.228499999999 0.000000000000 6714.682620000000 0.000000000000 0.000000000000 5000.000000000000 1411.428220000000 -6714.682620000000 0.000000000000 0.000000000000 -16161.228499999999 1411.428220000000 54257.687500000000 -1870.899410000000 -21620.652300000002 16161.228499999999 0.000000000000 -6714.682620000000 -1870.899410000000 61950.910199999998 -4465.795900000000 -1411.428220000000 6714.682620000000 0.000000000000 -21620.652300000002 -4465.795900000000 10476.555700000001 30 32 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11588.870100000000 -63.417301200000 0.000000000000 5000.000000000000 0.000000000000 -11588.870100000000 0.000000000000 4881.066890000000 0.000000000000 0.000000000000 5000.000000000000 63.417301200000 -4881.066890000000 0.000000000000 0.000000000000 -11588.870100000000 63.417301200000 30002.996100000000 80.755775500000 -11604.583000000001 11588.870100000000 0.000000000000 -4881.066890000000 80.755775500000 33657.878900000003 -284.390167000000 -63.417301200000 4881.066890000000 0.000000000000 -11604.583000000001 -284.390167000000 6112.544430000000 30 33 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11495.075199999999 -13.095477100000 0.000000000000 5000.000000000000 0.000000000000 -11495.075199999999 0.000000000000 4841.930180000000 0.000000000000 0.000000000000 5000.000000000000 13.095477100000 -4841.930180000000 0.000000000000 0.000000000000 -11495.075199999999 13.095477100000 29877.554700000001 142.606247000000 -11366.727500000001 11495.075199999999 0.000000000000 -4841.930180000000 142.606247000000 33174.570299999999 -287.192078000000 -13.095477100000 4841.930180000000 0.000000000000 -11366.727500000001 -287.192078000000 6291.166500000000 30 34 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11085.092800000000 -131.482513000000 0.000000000000 5000.000000000000 0.000000000000 -11085.092800000000 0.000000000000 4836.951660000000 0.000000000000 0.000000000000 5000.000000000000 131.482513000000 -4836.951660000000 0.000000000000 0.000000000000 -11085.092800000000 131.482513000000 27151.785199999998 -5.472912310000 -10938.628900000000 11085.092800000000 0.000000000000 -4836.951660000000 -5.472912310000 30947.168000000001 -122.999992000000 -131.482513000000 4836.951660000000 0.000000000000 -10938.628900000000 -122.999992000000 5760.403320000000 30 35 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 10961.842800000000 646.229065000000 0.000000000000 5000.000000000000 0.000000000000 -10961.842800000000 0.000000000000 4966.454590000000 0.000000000000 0.000000000000 5000.000000000000 -646.229065000000 -4966.454590000000 0.000000000000 0.000000000000 -10961.842800000000 -646.229065000000 26677.732400000001 816.927429000000 -11195.829100000001 10961.842800000000 0.000000000000 -4966.454590000000 816.927429000000 30822.119100000000 1835.253780000000 646.229065000000 4966.454590000000 0.000000000000 -11195.829100000001 1835.253780000000 5980.340820000000 30 36 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11293.085900000000 42.836586000000 0.000000000000 5000.000000000000 0.000000000000 -11293.085900000000 0.000000000000 4904.062010000000 0.000000000000 0.000000000000 5000.000000000000 -42.836586000000 -4904.062010000000 0.000000000000 0.000000000000 -11293.085900000000 -42.836586000000 28439.794900000001 199.421051000000 -11355.375000000000 11293.085900000000 0.000000000000 -4904.062010000000 199.421051000000 32100.615200000000 169.820923000000 42.836586000000 4904.062010000000 0.000000000000 -11355.375000000000 169.820923000000 6187.954590000000 30 37 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 11372.369100000000 -24.310367600000 0.000000000000 5000.000000000000 0.000000000000 -11372.369100000000 0.000000000000 4858.931640000000 0.000000000000 0.000000000000 5000.000000000000 24.310367600000 -4858.931640000000 0.000000000000 0.000000000000 -11372.369100000000 24.310367600000 28926.437500000000 49.608894300000 -11313.333000000001 11372.369100000000 0.000000000000 -4858.931640000000 49.608894300000 32492.683600000000 -468.212433000000 -24.310367600000 4858.931640000000 0.000000000000 -11313.333000000001 -468.212433000000 6081.726070000000 31 35 38 5000.000000000000 0.000000000000 0.000000000000 0.000000000000 9463.675780000000 369.308685000000 0.000000000000 5000.000000000000 0.000000000000 -9463.675780000000 0.000000000000 3076.667720000000 0.000000000000 0.000000000000 5000.000000000000 -369.308685000000 -3076.667720000000 0.000000000000 0.000000000000 -9463.675780000000 -369.308685000000 20420.474600000001 333.781342000000 -5871.425290000000 9463.675780000000 0.000000000000 -3076.667720000000 333.781342000000 21618.355500000001 1358.757570000000 369.308685000000 3076.667720000000 0.000000000000 -5871.425290000000 1358.757570000000 2805.967290000000 ================================================ FILE: common.py ================================================ import torch import torch.nn as nn import torch.nn.functional as F from utils.SE3 import * def rigid_transform_3d(A, B, weights=None, weight_threshold=0): """ Input: - A: [bs, num_corr, 3], source point cloud - B: [bs, num_corr, 3], target point cloud - weights: [bs, num_corr] weight for each correspondence - weight_threshold: float, clips points with weight below threshold Output: - R, t """ bs = A.shape[0] if weights is None: weights = torch.ones_like(A[:, :, 0]) weights[weights < weight_threshold] = 0 # weights = weights / (torch.sum(weights, dim=-1, keepdim=True) + 1e-6) # find mean of point cloud centroid_A = torch.sum(A * weights[:, :, None], dim=1, keepdim=True) / (torch.sum(weights, dim=1, keepdim=True)[:, :, None] + 1e-6) centroid_B = torch.sum(B * weights[:, :, None], dim=1, keepdim=True) / (torch.sum(weights, dim=1, keepdim=True)[:, :, None] + 1e-6) # subtract mean Am = A - centroid_A Bm = B - centroid_B # construct weight covariance matrix Weight = torch.diag_embed(weights) H = Am.permute(0, 2, 1) @ Weight @ Bm # find rotation U, S, Vt = torch.svd(H.cpu()) U, S, Vt = U.to(weights.device), S.to(weights.device), Vt.to(weights.device) delta_UV = torch.det(Vt @ U.permute(0, 2, 1)) eye = torch.eye(3)[None, :, :].repeat(bs, 1, 1).to(A.device) eye[:, -1, -1] = delta_UV R = Vt @ eye @ U.permute(0, 2, 1) t = centroid_B.permute(0,2,1) - R @ centroid_A.permute(0,2,1) # warp_A = transform(A, integrate_trans(R,t)) # RMSE = torch.sum( (warp_A - B) ** 2, dim=-1).mean() return integrate_trans(R, t) def knn(x, k, ignore_self=False, normalized=True): """ find feature space knn neighbor of x Input: - x: [bs, num_corr, num_channels], input features - k: - ignore_self: True/False, return knn include self or not. - normalized: True/False, if the feature x normalized. Output: - idx: [bs, num_corr, k], the indices of knn neighbors """ inner = 2 * torch.matmul(x, x.transpose(2, 1)) if normalized: pairwise_distance = 2 - inner else: xx = torch.sum(x ** 2, dim=-1, keepdim=True) pairwise_distance = xx - inner + xx.transpose(2, 1) if ignore_self is False: idx = pairwise_distance.topk(k=k, dim=-1, largest=False)[1] # (batch_size, num_points, k) else: idx = pairwise_distance.topk(k=k + 1, dim=-1, largest=False)[1][:, :, 1:] return idx class EdgeConv(nn.Module): def __init__(self, in_dim, out_dim, k, idx=None): super(EdgeConv, self).__init__() self.in_dim = in_dim self.out_dim = out_dim self.k = k self.idx = idx self.conv = nn.Conv2d(in_dim * 2, out_dim, kernel_size=1, bias=False) def forward(self, x): # x: [bs, in_dim, N] bs = x.shape[0] num_corr = x.shape[2] device = x.device # if self.idx is None: self.idx = knn(x.permute(0,2,1), self.k, normalized=False) idx_base = torch.arange(0, bs, device=device).view(-1, 1, 1) * num_corr idx = self.idx + idx_base idx = idx.view(-1) x = x.transpose(2, 1).contiguous() features = x.view(bs * num_corr, -1)[idx, :] features = features.view(bs, num_corr, self.k, self.in_dim) x = x.view(bs, num_corr, 1, self.in_dim).repeat(1, 1, self.k, 1) features = torch.cat([features - x, x], dim=3).permute(0, 3, 1, 2).contiguous() output = self.conv(features) output = output.max(dim=-1, keepdim=False)[0] return output class ContextNormalization(nn.Module): def __init__(self): super(ContextNormalization, self).__init__() def forward(self, x): var_eps = 1e-3 mean = torch.mean(x, 2, keepdim=True) variance = torch.var(x, 2, keepdim=True) x = (x - mean) / torch.sqrt(variance + var_eps) return x class PointCN(nn.Module): def __init__(self, in_dim=6, num_layers=6, num_channels=128, act_pos='post'): super(PointCN, self).__init__() assert act_pos == 'pre' or act_pos == 'post' modules = [nn.Conv1d(in_dim, num_channels, kernel_size=1, bias=True)] for i in range(num_layers): if act_pos == 'pre': modules.append(ContextNormalization()) modules.append(nn.BatchNorm1d(num_channels)) modules.append(nn.ReLU(inplace=True)) modules.append(nn.Conv1d(num_channels, num_channels, kernel_size=1, bias=True)) else: modules.append(nn.Conv1d(num_channels, num_channels, kernel_size=1, bias=True)) modules.append(ContextNormalization()) modules.append(nn.BatchNorm1d(num_channels)) modules.append(nn.ReLU(inplace=True)) self.encoder = nn.Sequential(*modules) def forward(self, x): features = self.encoder(x) return features ================================================ FILE: config.py ================================================ import argparse import time import os arg_lists = [] parser = argparse.ArgumentParser() def add_argument_group(name): arg = parser.add_argument_group(name) arg_lists.append(arg) return arg def str2bool(v): return v.lower() in ('true', '1') dataset = '3DMatch' experiment_id = f"PointDSC_{dataset}_{time.strftime('%m%d%H%M')}" # snapshot configurations snapshot_arg = add_argument_group('Snapshot') snapshot_arg.add_argument('--snapshot_dir', type=str, default=f'snapshot/{experiment_id}') snapshot_arg.add_argument('--tboard_dir', type=str, default=f'tensorboard/{experiment_id}') snapshot_arg.add_argument('--snapshot_interval', type=int, default=1) snapshot_arg.add_argument('--save_dir', type=str, default=os.path.join(f'snapshot/{experiment_id}', 'models/')) # Network configurations net_arg = add_argument_group('Network') net_arg.add_argument('--in_dim', type=int, default=6) net_arg.add_argument('--num_layers', type=int, default=12) net_arg.add_argument('--num_channels', type=int, default=128) net_arg.add_argument('--num_iterations', type=int, default=10, help='power iteration algorithm') net_arg.add_argument('--ratio', type=float, default=0.1, help='max ratio of seeding points') net_arg.add_argument('--k', type=int, default=40, help='size of local neighborhood') # Loss configurations loss_arg = add_argument_group('Loss') loss_arg.add_argument('--evaluate_interval', type=int, default=1) loss_arg.add_argument('--balanced', type=str2bool, default=False) loss_arg.add_argument('--weight_classification', type=float, default=1.0) loss_arg.add_argument('--weight_spectralmatching', type=float, default=1.0) loss_arg.add_argument('--weight_transformation', type=float, default=0.0) loss_arg.add_argument('--transformation_loss_start_epoch', type=int, default=0) # Optimizer configurations opt_arg = add_argument_group('Optimizer') opt_arg.add_argument('--optimizer', type=str, default='ADAM', choices=['SGD', 'ADAM']) opt_arg.add_argument('--max_epoch', type=int, default=50) opt_arg.add_argument('--training_max_iter', type=int, default=3500) opt_arg.add_argument('--val_max_iter', type=int, default=1000) opt_arg.add_argument('--lr', type=float, default=1e-4) opt_arg.add_argument('--weight_decay', type=float, default=1e-6) opt_arg.add_argument('--momentum', type=float, default=0.9) opt_arg.add_argument('--scheduler', type=str, default='ExpLR') opt_arg.add_argument('--scheduler_gamma', type=float, default=0.99) opt_arg.add_argument('--scheduler_interval', type=int, default=1) # Dataset and dataloader configurations data_arg = add_argument_group('Data') if dataset == '3DMatch': data_arg.add_argument('--root', type=str, default='/data/3DMatch') data_arg.add_argument('--descriptor', type=str, default='fcgf', choices=['d3feat', 'fpfh', 'fcgf']) data_arg.add_argument('--inlier_threshold', type=float, default=0.10) net_arg.add_argument('--sigma_d', type=float, default=0.10) data_arg.add_argument('--downsample', type=float, default=0.03) data_arg.add_argument('--re_thre', type=float, default=15, help='rotation error thrshold (deg)') data_arg.add_argument('--te_thre', type=float, default=30, help='translation error thrshold (cm)') else: data_arg.add_argument('--root', type=str, default='/data/KITTI') data_arg.add_argument('--descriptor', type=str, default='fcgf', choices=['fcgf', 'fpfh']) data_arg.add_argument('--inlier_threshold', type=float, default=1.2) net_arg.add_argument('--sigma_d', type=float, default=1.2) data_arg.add_argument('--downsample', type=float, default=0.30) data_arg.add_argument('--re_thre', type=float, default=5, help='rotation error thrshold (deg)') data_arg.add_argument('--te_thre', type=float, default=60, help='translation error thrshold (cm)') data_arg.add_argument('--num_node', type=int, default=1000) data_arg.add_argument('--use_mutual', type=str2bool, default=False) data_arg.add_argument('--augment_axis', type=int, default=3) data_arg.add_argument('--augment_rotation', type=float, default=1.0, help='rotation angle = num * 2pi') data_arg.add_argument('--augment_translation', type=float, default=0.5, help='translation = num (m)') data_arg.add_argument('--batch_size', type=int, default=16) data_arg.add_argument('--num_workers', type=int, default=16) # Other configurations misc_arg = add_argument_group('Misc') misc_arg.add_argument('--gpu_mode', type=str2bool, default=True) misc_arg.add_argument('--verbose', type=str2bool, default=True) misc_arg.add_argument('--pretrain', type=str, default='') misc_arg.add_argument('--weights_fixed', type=str2bool, default=False) def get_config(): args = parser.parse_args() return args ================================================ FILE: config_json/config_3DLoMatch.json ================================================ { "CUDA_Devices": "2", "num_iterations": 10, "dataset": "3DLoMatch", "ratio": 0.2, "k1": 30, "k2": 20, "data_path": "data/3DLoMatch", "descriptor": "predator", "inlier_threshold": 0.1, "sigma_d": 0.1, "d_thre": 0.1, "downsample": 0.05, "re_thre": 15, "te_thre": 30, "num_node": 5000, "use_mutual": false, "max_points": 8000, "nms_radius": 0.1 } ================================================ FILE: config_json/config_3DMatch.json ================================================ { "CUDA_Devices": "2", "num_iterations": 10, "dataset": "3DMatch", "ratio": 0.2, "k1": 30, "k2": 20, "data_path": "data/3DMatch", "descriptor": "fpfh", "inlier_threshold": 0.1, "sigma_d": 0.1, "d_thre": 0.1, "downsample": 0.05, "re_thre": 15, "te_thre": 30, "num_node": "all", "use_mutual": false, "max_points": 8000, "nms_radius": 0.1 } ================================================ FILE: config_json/config_KITTI.json ================================================ { "CUDA_Devices": "1", "num_iterations": 20, "dataset": "KITTI", "ratio": 0.2, "k1": 30, "k2": 20, "data_path": "data/KITTI/fpfh_test", "descriptor": "fpfh", "inlier_threshold": 0.6, "d_thre": 0.1, "downsample": 0.3, "re_thre": 5, "te_thre": 60, "num_node": 8000, "use_mutual": false, "max_points": 8000, "nms_radius": 0.6 } ================================================ FILE: dataset.py ================================================ import os import pickle import torch.utils.data as data from utils.SE3 import * import torch class ThreeDLoader(data.Dataset): def __init__(self, root, descriptor='fcgf', inlier_threshold=0.10, num_node=5000, downsample=0.03, use_mutual=False, select_scene=None, ): self.root = root self.descriptor = descriptor assert descriptor in ['fcgf', 'fpfh'] self.inlier_threshold = inlier_threshold self.num_node = num_node self.use_mutual = use_mutual self.sigma_spat = 0.1 self.num_iterations = 10 # maximum iteration of power iteration algorithm self.ratio = 0.1 # the maximum ratio of seeds. self.nms_radius = 0.1 # containers self.gt_trans = {} self.scene_list = [ '7-scenes-redkitchen', 'sun3d-home_at-home_at_scan1_2013_jan_1', 'sun3d-home_md-home_md_scan9_2012_sep_30', 'sun3d-hotel_uc-scan3', 'sun3d-hotel_umd-maryland_hotel1', 'sun3d-hotel_umd-maryland_hotel3', 'sun3d-mit_76_studyroom-76-1studyroom2', 'sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika' ] if select_scene in self.scene_list: self.scene_list = [select_scene] # load ground truth transformation for scene in self.scene_list: scene_path = f'{self.root}/fragments/{scene}' gt_path = f'{self.root}/gt_result/{scene}-evaluation' for k, v in self.__loadlog__(gt_path).items(): self.gt_trans[f'{scene}@{k}'] = v def get_data(self, index): key = list(self.gt_trans.keys())[index] scene = key.split('@')[0] src_id = key.split('@')[1].split('_')[0] tgt_id = key.split('@')[1].split('_')[1] # load point coordinates and pre-computed per-point local descriptors if self.descriptor == 'fcgf': src_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{src_id}_fcgf.npz") tgt_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{tgt_id}_fcgf.npz") src_keypts = src_data['xyz'] tgt_keypts = tgt_data['xyz'] src_features = src_data['feature'] tgt_features = tgt_data['feature'] elif self.descriptor == 'fpfh': src_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{src_id}_fpfh.npz") tgt_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{tgt_id}_fpfh.npz") src_keypts = src_data['xyz'] tgt_keypts = tgt_data['xyz'] src_features = src_data['feature'] tgt_features = tgt_data['feature'] src_features = src_features / (np.linalg.norm(src_features, axis=1, keepdims=True) + 1e-6) tgt_features = tgt_features / (np.linalg.norm(tgt_features, axis=1, keepdims=True) + 1e-6) # compute ground truth transformation gt_trans = np.linalg.inv(self.gt_trans[key]) # the given ground truth trans is target-> source return torch.from_numpy(src_keypts.astype(np.float32)).cuda()[None], \ torch.from_numpy(tgt_keypts.astype(np.float32)).cuda()[None], \ torch.from_numpy(src_features.astype(np.float32)).cuda()[None], \ torch.from_numpy(tgt_features.astype(np.float32)).cuda()[None], \ torch.from_numpy(gt_trans.astype(np.float32)).cuda()[None], \ def __len__(self): return self.gt_trans.keys().__len__() def __loadlog__(self, gtpath): with open(os.path.join(gtpath, 'gt.log')) as f: content = f.readlines() result = {} i = 0 while i < len(content): line = content[i].replace("\n", "").split("\t")[0:3] trans = np.zeros([4, 4]) trans[0] = np.fromstring(content[i+1], dtype=float, sep=' \t') trans[1] = np.fromstring(content[i+2], dtype=float, sep=' \t') trans[2] = np.fromstring(content[i+3], dtype=float, sep=' \t') trans[3] = np.fromstring(content[i+4], dtype=float, sep=' \t') i = i + 5 result[f'{int(line[0])}_{int(line[1])}'] = trans return result class ThreeDLoMatchLoader(data.Dataset): def __init__(self, root, descriptor='fcgf', inlier_threshold=0.10, num_node=5000, use_mutual=True, downsample=0.03, ): self.root = root self.descriptor = descriptor assert descriptor in ['fcgf', 'fpfh', 'predator'] self.inlier_threshold = inlier_threshold self.num_node = num_node self.use_mutual = use_mutual self.downsample = downsample with open('3DLoMatch.pkl', 'rb') as f: self.infos = pickle.load(f) def get_data(self, index): gt_trans = integrate_trans(self.infos['rot'][index], self.infos['trans'][index]) scene = self.infos['src'][index].split('/')[1] src_id = self.infos['src'][index].split('/')[-1].split('_')[-1].replace('.pth', '') tgt_id = self.infos['tgt'][index].split('/')[-1].split('_')[-1].replace('.pth', '') # load point coordinates and pre-computed per-point local descriptors if self.descriptor == 'fcgf': src_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{src_id}_fcgf.npz") tgt_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{tgt_id}_fcgf.npz") src_keypts = src_data['xyz'] tgt_keypts = tgt_data['xyz'] src_features = src_data['feature'] tgt_features = tgt_data['feature'] src_keypts = torch.from_numpy(src_keypts.astype(np.float32)).cuda() tgt_keypts = torch.from_numpy(tgt_keypts.astype(np.float32)).cuda() src_features = torch.from_numpy(src_features.astype(np.float32)).cuda() tgt_features = torch.from_numpy(tgt_features.astype(np.float32)).cuda() gt_trans = torch.from_numpy(gt_trans.astype(np.float32)).cuda() elif self.descriptor == 'fpfh': src_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{src_id}_fpfh.npz") tgt_data = np.load(f"{self.root}/fragments/{scene}/cloud_bin_{tgt_id}_fpfh.npz") src_keypts = src_data['xyz'] tgt_keypts = tgt_data['xyz'] src_features = src_data['feature'] tgt_features = tgt_data['feature'] src_features = src_features / (np.linalg.norm(src_features, axis=1, keepdims=True) + 1e-6) tgt_features = tgt_features / (np.linalg.norm(tgt_features, axis=1, keepdims=True) + 1e-6) src_keypts = torch.from_numpy(src_keypts.astype(np.float32)).cuda() tgt_keypts = torch.from_numpy(tgt_keypts.astype(np.float32)).cuda() src_features = torch.from_numpy(src_features.astype(np.float32)).cuda() tgt_features = torch.from_numpy(tgt_features.astype(np.float32)).cuda() gt_trans = torch.from_numpy(gt_trans.astype(np.float32)).cuda() elif self.descriptor == "predator": data_dict = torch.load( f'{self.root}/{index}.pth') len_src = data_dict['len_src'] src_keypts = data_dict['pcd'][:len_src, :].cuda() tgt_keypts = data_dict['pcd'][len_src:, :].cuda() src_features = data_dict['feats'][:len_src].cuda() tgt_features = data_dict['feats'][len_src:].cuda() saliency, overlap = data_dict['saliency'], data_dict['overlaps'] src_overlap, src_saliency = overlap[:len_src], saliency[:len_src] tgt_overlap, tgt_saliency = overlap[len_src:], saliency[len_src:] src_scores = src_overlap * src_saliency tgt_scores = tgt_overlap * tgt_saliency if (src_keypts.size(0) > self.num_node): idx = np.arange(src_keypts.size(0)) probs = (src_scores / src_scores.sum()).numpy().flatten() idx = np.random.choice(idx, size=self.num_node, replace=False, p=probs) src_keypts, src_features = src_keypts[idx], src_features[idx] if (tgt_keypts.size(0) > self.num_node): idx = np.arange(tgt_keypts.size(0)) probs = (tgt_scores / tgt_scores.sum()).numpy().flatten() idx = np.random.choice(idx, size=self.num_node, replace=False, p=probs) tgt_keypts, tgt_features = tgt_keypts[idx], tgt_features[idx] gt_trans = integrate_trans(data_dict['rot'], data_dict['trans']).cuda() return src_keypts[None], tgt_keypts[None], src_features[None], tgt_features[None], gt_trans[None] def __len__(self): return len(self.infos['rot']) class KITTILoader(data.Dataset): def __init__(self, root, descriptor='fcgf', inlier_threshold=0.60, num_node=5000, use_mutual=True, downsample=0.30 ): self.root = root self.descriptor = descriptor assert descriptor in ['fcgf', 'fpfh'] self.inlier_threshold = inlier_threshold self.num_node = num_node self.use_mutual = use_mutual self.downsample = downsample # containers self.ids_list = [] for filename in os.listdir(f"{self.root}/"): self.ids_list.append(os.path.join(f"{self.root}/", filename)) # self.ids_list = sorted(self.ids_list, key=lambda x: int(x.split('_')[-1].split('.')[0])) def get_data(self, index): # load meta data filename = self.ids_list[index] data = np.load(filename) src_keypts = data['xyz0'] tgt_keypts = data['xyz1'] src_features = data['features0'] tgt_features = data['features1'] if self.descriptor == 'fpfh': src_features = src_features / (np.linalg.norm(src_features, axis=1, keepdims=True) + 1e-6) tgt_features = tgt_features / (np.linalg.norm(tgt_features, axis=1, keepdims=True) + 1e-6) # compute ground truth transformation gt_trans = data['gt_trans'] return torch.from_numpy(src_keypts.astype(np.float32)).cuda()[None], \ torch.from_numpy(tgt_keypts.astype(np.float32)).cuda()[None], \ torch.from_numpy(src_features.astype(np.float32)).cuda()[None], \ torch.from_numpy(tgt_features.astype(np.float32)).cuda()[None], \ torch.from_numpy(gt_trans.astype(np.float32)).cuda()[None] def __len__(self): return len(self.ids_list) ================================================ FILE: environment.yml ================================================ name: SC2_PCR channels: - pytorch - open3d-admin - conda-forge - defaults dependencies: - _libgcc_mutex=0.1=main - absl-py=0.9.0=py37hc8dfbb8_1 - argon2-cffi=20.1.0=py37h7b6447c_1 - attrs=19.3.0=py_0 - backcall=0.2.0=py_0 - blas=1.0=mkl - bleach=3.1.5=py_0 - blinker=1.4=py_1 - brotlipy=0.7.0=py37h8f50634_1000 - c-ares=1.16.1=h516909a_0 - ca-certificates=2020.6.20=hecda079_0 - cachetools=4.1.1=py_0 - certifi=2020.6.20=py37hc8dfbb8_0 - cffi=1.14.1=py37he30daa8_0 - chardet=3.0.4=py37hc8dfbb8_1006 - click=7.1.2=pyh9f0ad1d_0 - cryptography=3.0=py37hb09aad4_0 - cudatoolkit=10.1.243=h6bb024c_0 - decorator=4.4.2=py_0 - defusedxml=0.6.0=py_0 - entrypoints=0.3=py37_0 - freetype=2.10.2=h5ab3b9f_0 - google-auth=1.20.1=py_0 - google-auth-oauthlib=0.4.1=py_2 - grpcio=1.31.0=py37hb0870dc_0 - idna=2.10=pyh9f0ad1d_0 - importlib-metadata=1.7.0=py37_0 - importlib_metadata=1.7.0=0 - intel-openmp=2020.1=217 - ipykernel=5.3.4=py37h5ca1d4c_0 - ipython=7.17.0=py37h39e3cac_0 - ipython_genutils=0.2.0=py37_0 - ipywidgets=7.5.1=py_0 - jedi=0.17.2=py37_0 - jinja2=2.11.2=py_0 - joblib=0.16.0=py_0 - jpeg=9b=h024ee3a_2 - jsonschema=3.2.0=py37_1 - jupyter_client=6.1.6=py_0 - jupyter_core=4.6.3=py37_0 - lcms2=2.11=h396b838_0 - ld_impl_linux-64=2.33.1=h53a641e_7 - libedit=3.1.20191231=h14c3975_1 - libffi=3.3=he6710b0_2 - libgcc-ng=9.1.0=hdf63c60_0 - libgfortran-ng=7.3.0=hdf63c60_0 - libpng=1.6.37=hbc83047_0 - libprotobuf=3.12.4=h8b12597_0 - libsodium=1.0.18=h7b6447c_0 - libstdcxx-ng=9.1.0=hdf63c60_0 - libtiff=4.1.0=h2733197_1 - lz4-c=1.9.2=he6710b0_1 - markdown=3.2.2=py_0 - markupsafe=1.1.1=py37h14c3975_1 - mistune=0.8.4=py37h14c3975_1001 - mkl=2020.1=217 - mkl-service=2.3.0=py37he904b0f_0 - mkl_fft=1.1.0=py37h23d657b_0 - mkl_random=1.1.1=py37h0573a6f_0 - nbconvert=5.6.1=py37_1 - nbformat=5.0.7=py_0 - ncurses=6.2=he6710b0_1 - ninja=1.10.0=py37hfd86e86_0 - notebook=6.1.1=py37_0 - numpy=1.19.1=py37hbc911f0_0 - numpy-base=1.19.1=py37hfa32c7d_0 - oauthlib=3.0.1=py_0 - olefile=0.46=py37_0 - open3d=0.9.0.0=py37_0 - openssl=1.1.1g=h516909a_1 - packaging=20.4=py_0 - pandoc=2.10=0 - pandocfilters=1.4.2=py37_1 - parso=0.7.0=py_0 - pexpect=4.8.0=py37_1 - pickleshare=0.7.5=py37_1001 - pillow=7.2.0=py37hb39fc2d_0 - pip=20.2.1=py37_0 - prometheus_client=0.8.0=py_0 - prompt-toolkit=3.0.5=py_0 - protobuf=3.12.4=py37h3340039_0 - ptyprocess=0.6.0=py37_0 - pyasn1=0.4.8=py_0 - pyasn1-modules=0.2.7=py_0 - pycparser=2.20=py_2 - pygments=2.6.1=py_0 - pyjwt=1.7.1=py_0 - pyopenssl=19.1.0=py_1 - pyparsing=2.4.7=py_0 - pyrsistent=0.16.0=py37h7b6447c_0 - pysocks=1.7.1=py37hc8dfbb8_1 - python=3.7.7=hcff3b4d_5 - python-dateutil=2.8.1=py_0 - python_abi=3.7=1_cp37m - pytorch=1.6.0=py3.7_cuda10.1.243_cudnn7.6.3_0 - pyzmq=19.0.1=py37he6710b0_1 - readline=8.0=h7b6447c_0 - requests=2.24.0=pyh9f0ad1d_0 - requests-oauthlib=1.3.0=pyh9f0ad1d_0 - rsa=4.6=pyh9f0ad1d_0 - scikit-learn=0.23.1=py37h423224d_0 - scipy=1.5.0=py37h0b6359f_0 - send2trash=1.5.0=py37_0 - setuptools=49.3.1=py37_0 - six=1.15.0=py_0 - sqlite=3.32.3=h62c20be_0 - tensorboard=2.3.0=py_0 - tensorboard-plugin-wit=1.6.0=pyh9f0ad1d_0 - tensorboardx=2.1=py_0 - terminado=0.8.3=py37_0 - testpath=0.4.4=py_0 - threadpoolctl=2.1.0=pyh5ca1d4c_0 - tk=8.6.10=hbc83047_0 - torchvision=0.7.0=py37_cu101 - tornado=6.0.4=py37h7b6447c_1 - traitlets=4.3.3=py37_0 - urllib3=1.25.10=py_0 - wcwidth=0.2.5=py_0 - webencodings=0.5.1=py37_1 - werkzeug=1.0.1=pyh9f0ad1d_0 - wheel=0.34.2=py37_0 - widgetsnbextension=3.5.1=py37_0 - xz=5.2.5=h7b6447c_0 - zeromq=4.3.2=he6710b0_2 - zipp=3.1.0=py_0 - zlib=1.2.11=h7b6447c_3 - zstd=1.4.5=h9ceee32_0 - pip: - easydict==1.9 - tqdm==4.48.2 prefix: ~/anaconda3/envs/SC2_PCR ================================================ FILE: evaluate_metric.py ================================================ import torch import torch.nn as nn import torch.nn.functional as F import numpy as np from sklearn.metrics import recall_score, precision_score, f1_score from utils.SE3 import * import warnings warnings.filterwarnings('ignore') class TransformationLoss(nn.Module): def __init__(self, re_thre=15, te_thre=30): super(TransformationLoss, self).__init__() self.re_thre = re_thre # rotation error threshold (deg) self.te_thre = te_thre # translation error threshold (cm) # def forward(self, trans, gt_trans, src_keypts, tgt_keypts, probs): def forward(self, trans, gt_trans, src_keypts, tgt_keypts, probs): """ Transformation Loss Inputs: - trans: [bs, 4, 4] SE3 transformation matrices - gt_trans: [bs, 4, 4] ground truth SE3 transformation matrices - src_keypts: [bs, num_corr, 3] - tgt_keypts: [bs, num_corr, 3] - probs: [bs, num_corr] predicted inlier probability Outputs: - loss transformation loss - recall registration recall (re < re_thre & te < te_thre) - RE rotation error - TE translation error - RMSE RMSE under the predicted transformation """ bs = trans.shape[0] R, t = decompose_trans(trans) gt_R, gt_t = decompose_trans(gt_trans) recall = 0 RE = torch.tensor(0.0).to(trans.device) TE = torch.tensor(0.0).to(trans.device) RMSE = torch.tensor(0.0).to(trans.device) loss = torch.tensor(0.0).to(trans.device) for i in range(bs): re = torch.acos(torch.clamp((torch.trace(R[i].T @ gt_R[i]) - 1) / 2.0, min=-1, max=1)) te = torch.sqrt(torch.sum((t[i] - gt_t[i]) ** 2)) warp_src_keypts = transform(src_keypts[i], trans[i]) rmse = torch.norm(warp_src_keypts - tgt_keypts, dim=-1).mean() re = re * 180 / np.pi te = te * 100 if te < self.te_thre and re < self.re_thre: recall += 1 RE += re TE += te RMSE += rmse pred_inliers = torch.where(probs[i] > 0)[0] if len(pred_inliers) < 1: loss += torch.tensor(0.0).to(trans.device) else: warp_src_keypts = transform(src_keypts[i], trans[i]) loss += ((warp_src_keypts - tgt_keypts)**2).sum(-1).mean() return loss / bs, recall * 100.0 / bs, RE / bs, TE / bs, RMSE / bs class ClassificationLoss(nn.Module): def __init__(self, balanced=True): super(ClassificationLoss, self).__init__() self.balanced = balanced def forward(self, pred, gt, weight=None): """ Classification Loss for the inlier confidence Inputs: - pred: [bs, num_corr] predicted logits/labels for the putative correspondences - gt: [bs, num_corr] ground truth labels Outputs:(dict) - loss (weighted) BCE loss for inlier confidence - precision: inlier precision (# kept inliers / # kepts matches) - recall: inlier recall (# kept inliers / # all inliers) - f1: (precision * recall * 2) / (precision + recall) - logits_true: average logits for inliers - logits_false: average logits for outliers """ num_pos = torch.relu(torch.sum(gt) - 1) + 1 num_neg = torch.relu(torch.sum(1 - gt) - 1) + 1 if weight is not None: loss = nn.BCEWithLogitsLoss(reduction='none')(pred, gt.float()) loss = torch.mean(loss * weight) elif self.balanced is False: loss = nn.BCEWithLogitsLoss(reduction='mean')(pred, gt.float()) else: loss = nn.BCEWithLogitsLoss(pos_weight=num_neg * 1.0 / num_pos, reduction='mean')(pred, gt.float()) # compute precision, recall, f1 pred_labels = pred > 0 gt, pred_labels, pred = gt.detach().cpu().numpy(), pred_labels.detach().cpu().numpy(), pred.detach().cpu().numpy() precision = precision_score(gt[0], pred_labels[0]) recall = recall_score(gt[0], pred_labels[0]) f1 = f1_score(gt[0], pred_labels[0]) mean_logit_true = np.sum(pred * gt) / max(1, np.sum(gt)) mean_logit_false = np.sum(pred * (1 - gt)) / max(1, np.sum(1 - gt)) eval_stats = { "loss": loss, "precision": float(precision), "recall": float(recall), "f1": float(f1), "logit_true": float(mean_logit_true), "logit_false": float(mean_logit_false) } return eval_stats ================================================ FILE: test_3DLoMatch.py ================================================ import json import sys sys.path.append('.') import argparse import logging from tqdm import tqdm from easydict import EasyDict as edict from evaluate_metric import TransformationLoss, ClassificationLoss from dataset import ThreeDLoMatchLoader from benchmark_utils import set_seed, icp_refine from benchmark_utils_predator import * from utils.timer import Timer from SC2_PCR import Matcher set_seed() from utils.SE3 import * from collections import defaultdict def eval_3DLoMatch_scene(loader, matcher, trans_evaluator, cls_evaluator, scene_ind, config): num_pair = loader.__len__() final_poses = np.zeros([num_pair, 4, 4]) # 0.success, 1.RE, 2.TE, 3.input inlier number, 4.input inlier ratio, 5. output inlier number # 6. output inlier precision, 7. output inlier recall, 8. output inlier F1 score 9. model_time, 10. data_time 11. scene_ind stats = np.zeros([num_pair, 12]) data_timer, model_timer = Timer(), Timer() with torch.no_grad(): error_pair = [] for i in tqdm(range(num_pair)): ################################# # 1. load data ################################# data_timer.tic() src_keypts, tgt_keypts, src_features, tgt_features, gt_trans = loader.get_data(i) data_time = data_timer.toc() ################################# # 2. match descriptor and compute rigid transformation ################################# model_timer.tic() pred_trans, pred_labels, src_keypts_corr, tgt_keypts_corr = matcher.estimator(src_keypts, tgt_keypts, src_features, tgt_features) model_time = model_timer.toc() ################################# # 3. generate the ground-truth classification result ################################# frag1_warp = transform(src_keypts_corr, gt_trans) distance = torch.sum((frag1_warp - tgt_keypts_corr) ** 2, dim=-1) ** 0.5 gt_labels = (distance < config.inlier_threshold).float() ################################# # 4. evaluate result ################################# loss, recall, Re, Te, rmse = trans_evaluator(pred_trans, gt_trans, src_keypts_corr, tgt_keypts_corr, pred_labels) class_stats = cls_evaluator(pred_labels, gt_labels) ################################# # record the evaluation results. ################################# # save statistics stats[i, 0] = float(recall / 100.0) # success stats[i, 1] = float(Re) # Re (deg) stats[i, 2] = float(Te) # Te (cm) stats[i, 3] = int(torch.sum(gt_labels)) # input inlier number stats[i, 4] = float(torch.mean(gt_labels.float())) # input inlier ratio stats[i, 5] = int(torch.sum(gt_labels[pred_labels > 0])) # output inlier number stats[i, 6] = float(class_stats['precision']) # output inlier precision stats[i, 7] = float(class_stats['recall']) # output inlier recall stats[i, 8] = float(class_stats['f1']) # output inlier f1 score stats[i, 9] = model_time stats[i, 10] = data_time stats[i, 11] = scene_ind final_poses[i] = pred_trans[0].detach().cpu().numpy() print(error_pair) return stats, final_poses def eval_3DLoMatch(config): loader = ThreeDLoMatchLoader(root=config.data_path, descriptor=config.descriptor, inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, ) matcher = Matcher(inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, d_thre=config.d_thre, num_iterations=config.num_iterations, ratio=config.ratio, nms_radius=config.nms_radius, max_points=config.max_points, k1=config.k1, k2=config.k2, ) trans_evaluator = TransformationLoss(re_thre=config.re_thre, te_thre=config.te_thre) cls_evaluator = ClassificationLoss() allpair_stats, allpair_poses = eval_3DLoMatch_scene(loader, matcher, trans_evaluator, cls_evaluator, 0, config) allpair_average = allpair_stats.mean(0) allpair_status_ndarray = np.array(allpair_stats, dtype=float) benchmark_predator(allpair_poses, gt_folder='benchmarks/3DLoMatch') # benchmarking using the registration recall defined in DGR allpair_average = allpair_stats.mean(0) correct_pair_average = allpair_stats[allpair_stats[:, 0] == 1].mean(0) logging.info(f"*" * 40) logging.info(f"All {allpair_stats.shape[0]} pairs, Mean Reg Recall={allpair_average[0] * 100:.2f}%, Mean Re={correct_pair_average[1]:.2f}, Mean Te={correct_pair_average[2]:.2f}") logging.info(f"\tInput: Mean Inlier Num={allpair_average[3]:.2f}(ratio={allpair_average[4] * 100:.2f}%)") logging.info(f"\tOutput: Mean Inlier Num={allpair_average[5]:.2f}(precision={allpair_average[6] * 100:.2f}%, recall={allpair_average[7] * 100:.2f}%, f1={allpair_average[8] * 100:.2f}%)") logging.info(f"\tMean model time: {allpair_average[9]:.2f}s, Mean data time: {allpair_average[10]:.2f}s") # all_stats_npy = np.concatenate([v for k, v in all_stats.items()], axis=0) return allpair_stats def benchmark_predator(pred_poses, gt_folder): scenes = sorted(os.listdir(gt_folder)) scene_names = [os.path.join(gt_folder,ele) for ele in scenes] re_per_scene = defaultdict(list) te_per_scene = defaultdict(list) re_all, te_all, precision, recall = [], [], [], [] n_valids= [] short_names=['Kitchen','Home 1','Home 2','Hotel 1','Hotel 2','Hotel 3','Study','MIT Lab'] logging.info(("Scene\t¦ prec.\t¦ rec.\t¦ re\t¦ te\t¦ samples\t¦")) start_ind = 0 for idx,scene in enumerate(scene_names): # ground truth info gt_pairs, gt_traj = read_trajectory(os.path.join(scene, "gt.log")) n_valid=0 for ele in gt_pairs: diff=abs(int(ele[0])-int(ele[1])) n_valid+=diff>1 n_valids.append(n_valid) n_fragments, gt_traj_cov = read_trajectory_info(os.path.join(scene,"gt.info")) # estimated info # est_pairs, est_traj = read_trajectory(os.path.join(est_folder,scenes[idx],'est.log')) est_traj = pred_poses[start_ind:start_ind + len(gt_pairs)] start_ind = start_ind + len(gt_pairs) temp_precision, temp_recall,c_flag = evaluate_registration(n_fragments, est_traj, gt_pairs, gt_pairs, gt_traj, gt_traj_cov) # Filter out the estimated rotation matrices ext_gt_traj = extract_corresponding_trajectors(gt_pairs,gt_pairs, gt_traj) re = rotation_error(torch.from_numpy(ext_gt_traj[:,0:3,0:3]), torch.from_numpy(est_traj[:,0:3,0:3])).cpu().numpy()[np.array(c_flag)==0] te = translation_error(torch.from_numpy(ext_gt_traj[:,0:3,3:4]), torch.from_numpy(est_traj[:,0:3,3:4])).cpu().numpy()[np.array(c_flag)==0] re_per_scene['mean'].append(np.mean(re)) re_per_scene['median'].append(np.median(re)) re_per_scene['min'].append(np.min(re)) re_per_scene['max'].append(np.max(re)) te_per_scene['mean'].append(np.mean(te)) te_per_scene['median'].append(np.median(te)) te_per_scene['min'].append(np.min(te)) te_per_scene['max'].append(np.max(te)) re_all.extend(re.reshape(-1).tolist()) te_all.extend(te.reshape(-1).tolist()) precision.append(temp_precision) recall.append(temp_recall) logging.info("{}\t¦ {:.3f}\t¦ {:.3f}\t¦ {:.3f}\t¦ {:.3f}\t¦ {:3d}¦".format(short_names[idx], temp_precision, temp_recall, np.median(re), np.median(te), n_valid)) # np.save(f'{est_folder}/{scenes[idx]}/flag.npy',c_flag) weighted_precision = (np.array(n_valids) * np.array(precision)).sum() / np.sum(n_valids) logging.info("Mean precision: {:.3f}: +- {:.3f}".format(np.mean(precision),np.std(precision))) logging.info("Weighted precision: {:.3f}".format(weighted_precision)) logging.info("Mean median RRE: {:.3f}: +- {:.3f}".format(np.mean(re_per_scene['median']), np.std(re_per_scene['median']))) logging.info("Mean median RTE: {:.3F}: +- {:.3f}".format(np.mean(te_per_scene['median']),np.std(te_per_scene['median']))) if __name__ == '__main__': from config import str2bool parser = argparse.ArgumentParser() parser.add_argument('--config_path', default='', type=str, help='snapshot dir') parser.add_argument('--solver', default='SVD', type=str, choices=['SVD', 'RANSAC']) parser.add_argument('--use_icp', default=False, type=str2bool) parser.add_argument('--save_npy', default=False, type=str2bool) args = parser.parse_args() config_path = args.config_path config = json.load(open(config_path, 'r')) config = edict(config) import os os.environ['CUDA_VISIBLE_DEVICES'] = config.CUDA_Devices if not os.path.exists("./logs"): os.makedirs("./logs") log_filename = f'logs/3DLoMatch-{config.descriptor}.log' logging.basicConfig(level=logging.INFO, filename=log_filename, filemode='a', format="") logging.getLogger().addHandler(logging.StreamHandler(sys.stdout)) # evaluate on the test set stats = eval_3DLoMatch(config) if args.save_npy: save_path = log_filename.replace('.log', '.npy') np.save(save_path, stats) print(f"Save the stats in {save_path}") ================================================ FILE: test_3DMatch.py ================================================ import json import sys sys.path.append('.') import argparse import logging import torch import numpy as np from tqdm import tqdm from easydict import EasyDict as edict from evaluate_metric import TransformationLoss, ClassificationLoss from dataset import ThreeDLoader from benchmark_utils import set_seed, icp_refine from utils.timer import Timer from SC2_PCR import Matcher set_seed() from utils.SE3 import transform def eval_3DMatch_scene(loader, matcher, trans_evaluator, cls_evaluator, scene, scene_ind, config, use_icp): """ Evaluate our model on 3DMatch testset [scene] """ num_pair = loader.__len__() # 0.success, 1.RE, 2.TE, 3.input inlier number, 4.input inlier ratio, 5. output inlier number # 6. output inlier precision, 7. output inlier recall, 8. output inlier F1 score 9. model_time, 10. data_time 11. scene_ind stats = np.zeros([num_pair, 12]) data_timer, model_timer = Timer(), Timer() with torch.no_grad(): error_pair = [] for i in tqdm(range(num_pair)): ################################# # 1. load data ################################# data_timer.tic() src_keypts, tgt_keypts, src_features, tgt_features, gt_trans = loader.get_data(i) data_time = data_timer.toc() ################################# # 2. match descriptor and compute rigid transformation ################################# model_timer.tic() pred_trans, pred_labels, src_keypts_corr, tgt_keypts_corr = matcher.estimator(src_keypts, tgt_keypts, src_features, tgt_features) model_time = model_timer.toc() ################################# # 3. generate the ground-truth classification result ################################# frag1_warp = transform(src_keypts_corr, gt_trans) distance = torch.sum((frag1_warp - tgt_keypts_corr) ** 2, dim = -1) ** 0.5 gt_labels = (distance < config.inlier_threshold).float() ################################# # 4. evaluate result ################################# loss, recall, Re, Te, rmse = trans_evaluator(pred_trans, gt_trans, src_keypts_corr, tgt_keypts_corr, pred_labels) class_stats = cls_evaluator(pred_labels, gt_labels) ################################# # 5. svae the result ################################# stats[i, 0] = float(recall / 100.0) # success stats[i, 1] = float(Re) # Re (deg) stats[i, 2] = float(Te) # Te (cm) stats[i, 3] = int(torch.sum(gt_labels)) # input inlier number stats[i, 4] = float(torch.mean(gt_labels.float())) # input inlier ratio stats[i, 5] = int(torch.sum(gt_labels[pred_labels > 0])) # output inlier number stats[i, 6] = float(class_stats['precision']) # output inlier precision stats[i, 7] = float(class_stats['recall']) # output inlier recall stats[i, 8] = float(class_stats['f1']) # output inlier f1 score stats[i, 9] = model_time stats[i, 10] = data_time stats[i, 11] = scene_ind print(error_pair) return stats def eval_3DMatch(config, use_icp): """ Collect the evaluation results on each scene of 3DMatch testset, write the result to a .log file. """ scene_list = [ '7-scenes-redkitchen', 'sun3d-home_at-home_at_scan1_2013_jan_1', 'sun3d-home_md-home_md_scan9_2012_sep_30', 'sun3d-hotel_uc-scan3', 'sun3d-hotel_umd-maryland_hotel1', 'sun3d-hotel_umd-maryland_hotel3', 'sun3d-mit_76_studyroom-76-1studyroom2', 'sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika' ] all_stats = {} for scene_ind, scene in enumerate(scene_list): loader = ThreeDLoader(root=config.data_path, descriptor=config.descriptor, inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, select_scene=scene, ) matcher = Matcher(inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, d_thre=config.d_thre, num_iterations=config.num_iterations, ratio=config.ratio, nms_radius=config.nms_radius, max_points=config.max_points, k1=config.k1, k2=config.k2,) trans_evaluator = TransformationLoss(re_thre=config.re_thre, te_thre=config.te_thre) cls_evaluator = ClassificationLoss() scene_stats = eval_3DMatch_scene(loader, matcher, trans_evaluator, cls_evaluator, scene, scene_ind, config, use_icp) all_stats[scene] = scene_stats logging.info(f"Max memory allicated: {torch.cuda.max_memory_allocated() / 1024 ** 3:.2f}GB") # result for each scene scene_vals = np.zeros([len(scene_list), 12]) scene_ind = 0 for scene, stats in all_stats.items(): correct_pair = np.where(stats[:, 0] == 1) scene_vals[scene_ind] = stats.mean(0) # for Re and Te, we only average over the successfully matched pairs. scene_vals[scene_ind, 1] = stats[correct_pair].mean(0)[1] scene_vals[scene_ind, 2] = stats[correct_pair].mean(0)[2] logging.info(f"Scene {scene_ind}th:" f" Reg Recall={scene_vals[scene_ind, 0] * 100:.2f}% " f" Mean RE={scene_vals[scene_ind, 1]:.2f} " f" Mean TE={scene_vals[scene_ind, 2]:.2f} " f" Mean Precision={scene_vals[scene_ind, 6] * 100:.2f}% " f" Mean Recall={scene_vals[scene_ind, 7] * 100:.2f}% " f" Mean F1={scene_vals[scene_ind, 8] * 100:.2f}%" ) scene_ind += 1 # scene level average average = scene_vals.mean(0) logging.info(f"All {len(scene_list)} scenes, Mean Reg Recall={average[0] * 100:.2f}%, Mean Re={average[1]:.2f}, Mean Te={average[2]:.2f}") logging.info(f"\tInput: Mean Inlier Num={average[3]:.2f}(ratio={average[4] * 100:.2f}%)") logging.info(f"\tOutput: Mean Inlier Num={average[5]:.2f}(precision={average[6] * 100:.2f}%, recall={average[7] * 100:.2f}%, f1={average[8] * 100:.2f}%)") logging.info(f"\tMean model time: {average[9]:.2f}s, Mean data time: {average[10]:.2f}s") # pair level average stats_list = [stats for _, stats in all_stats.items()] allpair_stats = np.concatenate(stats_list, axis=0) allpair_average = allpair_stats.mean(0) correct_pair_average = allpair_stats[allpair_stats[:, 0] == 1].mean(0) logging.info(f"*" * 40) logging.info(f"All {allpair_stats.shape[0]} pairs, Mean Reg Recall={allpair_average[0] * 100:.2f}%, Mean Re={correct_pair_average[1]:.2f}, Mean Te={correct_pair_average[2]:.2f}") logging.info(f"\tInput: Mean Inlier Num={allpair_average[3]:.2f}(ratio={allpair_average[4] * 100:.2f}%)") logging.info(f"\tOutput: Mean Inlier Num={allpair_average[5]:.2f}(precision={allpair_average[6] * 100:.2f}%, recall={allpair_average[7] * 100:.2f}%, f1={allpair_average[8] * 100:.2f}%)") logging.info(f"\tMean model time: {allpair_average[9]:.2f}s, Mean data time: {allpair_average[10]:.2f}s") all_stats_npy = np.concatenate([v for k, v in all_stats.items()], axis=0) return all_stats_npy if __name__ == '__main__': from config import str2bool parser = argparse.ArgumentParser() parser.add_argument('--config_path', default='', type=str, help='snapshot dir') parser.add_argument('--solver', default='SVD', type=str, choices=['SVD', 'RANSAC']) parser.add_argument('--use_icp', default=False, type=str2bool) parser.add_argument('--save_npy', default=False, type=str2bool) args = parser.parse_args() config_path = args.config_path config = json.load(open(config_path, 'r')) config = edict(config) import os os.environ['CUDA_VISIBLE_DEVICES'] = config.CUDA_Devices if not os.path.exists("./logs"): os.makedirs("./logs") log_filename = f'logs/3DMatch-{config.descriptor}.log' logging.basicConfig(level=logging.INFO, filename=log_filename, filemode='a', format="") logging.getLogger().addHandler(logging.StreamHandler(sys.stdout)) # evaluate on the test set stats = eval_3DMatch(config, args.use_icp) if args.save_npy: save_path = log_filename.replace('.log', '.npy') np.save(save_path, stats) print(f"Save the stats in {save_path}") ================================================ FILE: test_KITTI.py ================================================ import json import sys sys.path.append('.') import argparse import logging from tqdm import tqdm from easydict import EasyDict as edict from evaluate_metric import TransformationLoss, ClassificationLoss from dataset import KITTILoader from benchmark_utils import set_seed, icp_refine from benchmark_utils_predator import * from utils.timer import Timer from SC2_PCR import Matcher set_seed() from utils.SE3 import * def eval_KITTI_per_pair(loader, matcher, trans_evaluator, cls_evaluator, config): """ Evaluate our model on KITTI testset. """ num_pair = loader.__len__() # 0.success, 1.RE, 2.TE, 3.input inlier number, 4.input inlier ratio, 5. output inlier number # 6. output inlier precision, 7. output inlier recall, 8. output inlier F1 score 9. model_time, 10. data_time 11. scene_ind stats = np.zeros([num_pair, 12]) data_timer, model_timer = Timer(), Timer() with torch.no_grad(): for i in tqdm(range(num_pair)): ################################# # 1. load data ################################# data_timer.tic() src_keypts, tgt_keypts, src_features, tgt_features, gt_trans = loader.get_data(i) data_time = data_timer.toc() ################################# # 2. match descriptor and compute rigid transformation ################################# model_timer.tic() pred_trans, pred_labels, src_keypts_corr, tgt_keypts_corr = matcher.estimator(src_keypts, tgt_keypts, src_features, tgt_features) model_time = model_timer.toc() ################################# # 3. generate the ground-truth classification result ################################# frag1_warp = transform(src_keypts_corr, gt_trans) distance = torch.sum((frag1_warp - tgt_keypts_corr) ** 2, dim=-1) ** 0.5 gt_labels = (distance < config.inlier_threshold).float() ################################# # 4. evaluate result ################################# loss, recall, Re, Te, rmse = trans_evaluator(pred_trans, gt_trans, src_keypts_corr, tgt_keypts_corr, pred_labels) class_stats = cls_evaluator(pred_labels, gt_labels) # save statistics stats[i, 0] = float(recall / 100.0) # success stats[i, 1] = float(Re) # Re (deg) stats[i, 2] = float(Te) # Te (cm) stats[i, 3] = int(torch.sum(gt_labels)) # input inlier number stats[i, 4] = float(torch.mean(gt_labels.float())) # input inlier ratio stats[i, 5] = int(torch.sum(gt_labels[pred_labels > 0])) # output inlier number stats[i, 6] = float(class_stats['precision']) # output inlier precision stats[i, 7] = float(class_stats['recall']) # output inlier recall stats[i, 8] = float(class_stats['f1']) # output inlier f1 score stats[i, 9] = model_time stats[i, 10] = data_time stats[i, 11] = -1 if recall == 0: from benchmark_utils import rot_to_euler R_gt, t_gt = gt_trans[0][:3, :3], gt_trans[0][:3, -1] euler = rot_to_euler(R_gt.detach().cpu().numpy()) input_ir = float(torch.mean(gt_labels.float())) input_i = int(torch.sum(gt_labels)) output_i = int(torch.sum(gt_labels[pred_labels > 0])) logging.info(f"Pair {i}, GT Rot: {euler[0]:.2f}, {euler[1]:.2f}, {euler[2]:.2f}, Trans: {t_gt[0]:.2f}, {t_gt[1]:.2f}, {t_gt[2]:.2f}, RE: {float(Re):.2f}, TE: {float(Te):.2f}") logging.info((f"\tInput Inlier Ratio :{input_ir*100:.2f}%(#={input_i}), Output: IP={float(class_stats['precision'])*100:.2f}%(#={output_i}) IR={float(class_stats['recall'])*100:.2f}%")) return stats def eval_KITTI(config): loader = KITTILoader(root=config.data_path, descriptor=config.descriptor, inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, ) matcher = Matcher(inlier_threshold=config.inlier_threshold, num_node=config.num_node, use_mutual=config.use_mutual, d_thre=config.d_thre, num_iterations=config.num_iterations, ratio=config.ratio, nms_radius=config.nms_radius, max_points=config.max_points, k1=config.k1, k2=config.k2, ) trans_evaluator = TransformationLoss(re_thre=config.re_thre, te_thre=config.te_thre) cls_evaluator = ClassificationLoss() stats = eval_KITTI_per_pair(loader, matcher, trans_evaluator, cls_evaluator, config) logging.info(f"Max memory allicated: {torch.cuda.max_memory_allocated() / 1024 ** 3:.2f}GB") # pair level average allpair_stats = stats allpair_average = allpair_stats.mean(0) correct_pair_average = allpair_stats[allpair_stats[:, 0] == 1].mean(0) logging.info(f"*"*40) logging.info(f"All {allpair_stats.shape[0]} pairs, Mean Success Rate={allpair_average[0]*100:.2f}%, Mean Re={correct_pair_average[1]:.2f}, Mean Te={correct_pair_average[2]:.2f}") logging.info(f"\tInput: Mean Inlier Num={allpair_average[3]:.2f}(ratio={allpair_average[4]*100:.2f}%)") logging.info(f"\tOutput: Mean Inlier Num={allpair_average[5]:.2f}(precision={allpair_average[6]*100:.2f}%, recall={allpair_average[7]*100:.2f}%, f1={allpair_average[8]*100:.2f}%)") logging.info(f"\tMean model time: {allpair_average[9]:.2f}s, Mean data time: {allpair_average[10]:.2f}s") return allpair_stats if __name__ == '__main__': from config import str2bool parser = argparse.ArgumentParser() parser.add_argument('--config_path', default='', type=str, help='snapshot dir') parser.add_argument('--solver', default='SVD', type=str, choices=['SVD', 'RANSAC']) parser.add_argument('--use_icp', default=False, type=str2bool) parser.add_argument('--save_npz', default=False, type=str2bool) args = parser.parse_args() config_path = args.config_path config = json.load(open(config_path, 'r')) config = edict(config) import os os.environ['CUDA_VISIBLE_DEVICES'] = config.CUDA_Devices if not os.path.exists("./logs"): os.makedirs("./logs") log_filename = f'logs/KITTI-{config.descriptor}.log' logging.basicConfig(level=logging.INFO, filename=log_filename, filemode='a', format="") logging.getLogger().addHandler(logging.StreamHandler(sys.stdout)) stats = eval_KITTI(config) if args.save_npz: save_path = log_filename.replace('.log', '.npy') np.save(save_path, stats) print(f"Save the stats in {save_path}") ================================================ FILE: utils/SE3.py ================================================ import torch import random import numpy as np def rotation_matrix(num_axis, augment_rotation): """ Sample rotation matrix along [num_axis] axis and [0 - augment_rotation] angle Input - num_axis: rotate along how many axis - augment_rotation: rotate by how many angle Output - R: [3, 3] rotation matrix """ assert num_axis == 1 or num_axis == 3 or num_axis == 0 if num_axis == 0: return np.eye(3) angles = np.random.rand(3) * 2 * np.pi * augment_rotation Rx = np.array([[1, 0, 0], [0, np.cos(angles[0]), -np.sin(angles[0])], [0, np.sin(angles[0]), np.cos(angles[0])]]) Ry = np.array([[np.cos(angles[1]), 0, np.sin(angles[1])], [0, 1, 0], [-np.sin(angles[1]), 0, np.cos(angles[1])]]) Rz = np.array([[np.cos(angles[2]), -np.sin(angles[2]), 0], [np.sin(angles[2]), np.cos(angles[2]), 0], [0, 0, 1]]) # R = Rx @ Ry @ Rz if num_axis == 1: return random.choice([Rx, Ry, Rz]) return Rx @ Ry @ Rz def translation_matrix(augment_translation): """ Sample translation matrix along 3 axis and [augment_translation] meter Input - augment_translation: translate by how many meters Output - t: [3, 1] translation matrix """ T = np.random.rand(3) * augment_translation return T.reshape(3, 1) def transform(pts, trans): """ Applies the SE3 transformations, support torch.Tensor and np.ndarry. Equation: trans_pts = R @ pts + t Input - pts: [num_pts, 3] or [bs, num_pts, 3], pts to be transformed - trans: [4, 4] or [bs, 4, 4], SE3 transformation matrix Output - pts: [num_pts, 3] or [bs, num_pts, 3] transformed pts """ if len(pts.shape) == 3: trans_pts = trans[:, :3, :3] @ pts.permute(0,2,1) + trans[:, :3, 3:4] return trans_pts.permute(0,2,1) else: trans_pts = trans[:3, :3] @ pts.T + trans[:3, 3:4] return trans_pts.T def decompose_trans(trans): """ Decompose SE3 transformations into R and t, support torch.Tensor and np.ndarry. Input - trans: [4, 4] or [bs, 4, 4], SE3 transformation matrix Output - R: [3, 3] or [bs, 3, 3], rotation matrix - t: [3, 1] or [bs, 3, 1], translation matrix """ if len(trans.shape) == 3: return trans[:, :3, :3], trans[:, :3, 3:4] else: return trans[:3, :3], trans[:3, 3:4] def integrate_trans(R, t): """ Integrate SE3 transformations from R and t, support torch.Tensor and np.ndarry. Input - R: [3, 3] or [bs, 3, 3], rotation matrix - t: [3, 1] or [bs, 3, 1], translation matrix Output - trans: [4, 4] or [bs, 4, 4], SE3 transformation matrix """ if len(R.shape) == 3: if isinstance(R, torch.Tensor): trans = torch.eye(4)[None].repeat(R.shape[0], 1, 1).to(R.device) else: trans = np.eye(4)[None] trans[:, :3, :3] = R trans[:, :3, 3:4] = t.view([-1, 3, 1]) else: if isinstance(R, torch.Tensor): trans = torch.eye(4).to(R.device) else: trans = np.eye(4) trans[:3, :3] = R trans[:3, 3:4] = t return trans def concatenate(trans1, trans2): """ Concatenate two SE3 transformations, support torch.Tensor and np.ndarry. Input - trans1: [4, 4] or [bs, 4, 4], SE3 transformation matrix - trans2: [4, 4] or [bs, 4, 4], SE3 transformation matrix Output: - trans1 @ trans2 """ R1, t1 = decompose_trans(trans1) R2, t2 = decompose_trans(trans2) R_cat = R1 @ R2 t_cat = R1 @ t2 + t1 trans_cat = integrate_trans(R_cat, t_cat) return trans_cat ================================================ FILE: utils/max_clique.py ================================================ #!/usr/bin/python # -*- coding: utf-8 -*- ''' Code borrowed from https://github.com/ryanrossi/pmc/blob/master/pmc.py Find maxumum clique in given dimacs-format graph based on: http://www.m-hikari.com/ams/ams-2014/ams-1-4-2014/mamatAMS1-4-2014-3.pdf ''' import os import numpy as np from numpy.ctypeslib import ndpointer import ctypes def pmc(ei,ej,nnodes,nnedges): #ei, ej is edge list whose index starts from 0 degrees = np.zeros(nnodes,dtype = np.int32) new_ei = [] new_ej = [] for i in range(nnedges): degrees[ei[i]] += 1 if ej[i] <= ei[i] + 1: new_ei.append(ei[i]) new_ej.append(ej[i]) maxd = max(degrees) offset = 0 new_ei = np.array(new_ei,dtype = np.int32) new_ej = np.array(new_ej,dtype = np.int32) outsize = maxd output = np.zeros(maxd,dtype = np.int32) lib = ctypes.cdll.LoadLibrary(os.path.abspath("utils/libpmc.so")) fun = lib.max_clique #call C function fun.restype = np.int32 fun.argtypes = [ctypes.c_int32,ndpointer(ctypes.c_int32, flags="C_CONTIGUOUS"), ndpointer(ctypes.c_int32, flags="C_CONTIGUOUS"),ctypes.c_int32, ctypes.c_int32,ndpointer(ctypes.c_int32, flags="C_CONTIGUOUS")] clique_size = fun(len(new_ei),new_ei,new_ej,offset,outsize,output) max_clique = np.empty(clique_size,dtype = np.int32) max_clique[:]=[output[i] for i in range(clique_size)] return max_clique ================================================ FILE: utils/pointcloud.py ================================================ import open3d as o3d import torch def make_point_cloud(pts): if isinstance(pts, torch.Tensor): pts = pts.detach().cpu().numpy() pcd = o3d.geometry.PointCloud() pcd.points = o3d.utility.Vector3dVector(pts) return pcd def make_feature(data, dim, npts): if isinstance(data, torch.Tensor): data = data.detach().cpu().numpy() feature = o3d.registration.Feature() feature.resize(dim, npts) feature.data = data.astype('d').transpose() return feature def estimate_normal(pcd, radius=0.06, max_nn=30): pcd.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=radius, max_nn=max_nn)) ================================================ FILE: utils/sinkhorn.py ================================================ import torch ''' Reference: https://github.com/magicleap/SuperGluePretrainedNetwork/blob/c0626d58c843ee0464b0fa1dd4de4059bfae0ab4/models/superglue.py#L150 ''' def log_sinkhorn_iterations(Z, log_mu, log_nu, iters: int): ''' Perform Sinkhorn Normalization in Log-space for stability :param Z: :param log_mu: :param log_nu: :param iters: :return: ''' u, v = torch.zeros_like(log_mu), torch.zeros_like(log_nu) for _ in range(iters): u = log_mu - torch.logsumexp(Z + v.unsqueeze(1), dim=2) v = log_nu - torch.logsumexp(Z + u.unsqueeze(2), dim=1) return Z + u.unsqueeze(2) + v.unsqueeze(1) def log_optimal_transport(scores, bins0=None, bins1=None, alpha=None, iters=100): ''' Perform Differentiable Optimal Transport in Log-space for stability :param scores: :param alpha: :param iters: :return: ''' b, m, n = scores.shape one = scores.new_tensor(1) ms, ns = (m * one).to(scores), (n * one).to(scores) if bins0 is None: bins0 = alpha.expand(b, m, 1) if bins1 is None: bins1 = alpha.expand(b, 1, n) alpha = alpha.expand(b, 1, 1) couplings = torch.cat([torch.cat([scores, bins0], -1), torch.cat([bins1, alpha], -1)], 1) norm = - (ms + ns).log() log_mu = torch.cat([norm.expand(m), ns.log()[None] + norm]) log_nu = torch.cat([norm.expand(n), ms.log()[None] + norm]) log_mu, log_nu = log_mu[None].expand(b, -1), log_nu[None].expand(b, -1) Z = log_sinkhorn_iterations(couplings, log_mu, log_nu, iters) Z = Z - norm #multiply probabilities by M + N return Z def rpmnet_sinkhorn(log_score, bins0, bins1, iters: int): b, m, n = log_score.shape alpha = torch.zeros(size=(b, 1, 1)).cuda() log_score_padded = torch.cat([torch.cat([log_score, bins0], -1), torch.cat([bins1, alpha], -1)], 1) for i in range(iters): #Row Normalization log_score_padded = torch.cat(( log_score_padded[:, :-1, :] - (torch.logsumexp(log_score_padded[:, :-1, :], dim=2, keepdim=True)), log_score_padded[:, -1, None, :]), dim=1) #Column Normalization log_score_padded = torch.cat(( log_score_padded[:, :, :-1] - (torch.logsumexp(log_score_padded[:, :, :-1], dim=1, keepdim=True)), log_score_padded[:, :, -1, None]), dim=2) return log_score_padded ================================================ FILE: utils/timer.py ================================================ import time class AverageMeter(object): """Computes and stores the average and current value""" def __init__(self): self.reset() def reset(self): self.val = 0 self.avg = 0 self.sum = 0.0 self.sq_sum = 0.0 self.count = 0 def update(self, val, n=1): self.val = val self.sum += val * n self.count += n self.avg = self.sum / self.count self.sq_sum += val**2 * n self.var = self.sq_sum / self.count - self.avg ** 2 class Timer(object): """A simple timer.""" def __init__(self): self.total_time = 0. self.calls = 0 self.start_time = 0. self.diff = 0. self.avg = 0. def reset(self): self.total_time = 0 self.calls = 0 self.start_time = 0 self.diff = 0 self.avg = 0 def tic(self): # using time.time instead of time.clock because time time.clock # does not normalize for multithreading self.start_time = time.time() def toc(self, average=True): self.diff = time.time() - self.start_time self.total_time += self.diff self.calls += 1 self.avg = self.total_time / self.calls if average: return self.avg else: return self.diff